Merge bugfix-1.1.x

This commit is contained in:
Scott Lahteine
2018-09-29 19:29:48 -05:00
451 changed files with 181053 additions and 33377 deletions

46
.github/code_of_conduct.md vendored Normal file
View File

@@ -0,0 +1,46 @@
# Contributor Covenant Code of Conduct
## Our Pledge
In the interest of fostering an open and welcoming environment, we as contributors and maintainers pledge to making participation in our project and our community a harassment-free experience for everyone, regardless of age, body size, disability, ethnicity, gender identity and expression, level of experience, nationality, personal appearance, race, religion, or sexual identity and orientation.
## Our Standards
Examples of behavior that contributes to creating a positive environment include:
* Using welcoming and inclusive language
* Being respectful of differing viewpoints and experiences
* Gracefully accepting constructive criticism
* Focusing on what is best for the community
* Showing empathy towards other community members
Examples of unacceptable behavior by participants include:
* The use of sexualized language or imagery and unwelcome sexual attention or advances
* Trolling, insulting/derogatory comments, and personal or political attacks
* Public or private harassment
* Publishing others' private information, such as a physical or electronic address, without explicit permission
* Other conduct which could reasonably be considered inappropriate in a professional setting
## Our Responsibilities
Project maintainers are responsible for clarifying the standards of acceptable behavior and are expected to take appropriate and fair corrective action in response to any instances of unacceptable behavior.
Project maintainers have the right and responsibility to remove, edit, or reject comments, commits, code, issues, and other contributions that are not aligned to this Code of Conduct, or to ban temporarily or permanently any contributor for other behaviors that they deem inappropriate, threatening, offensive, or harmful.
## Scope
This Code of Conduct applies both within project spaces and in public spaces when an individual is representing the project or its community. Examples of representing a project or community include using an official project e-mail address, posting via an official social media account, or acting as an appointed representative at an online or offline event. Representation of a project may be further defined and clarified by project maintainers.
## Enforcement
Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by contacting the project team at [marlinfirmware@github.com](mailto:marlinfirmware@github.com). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. The project team is obligated to maintain confidentiality with regard to the reporter of an incident. Further details of specific enforcement policies may be posted separately.
Project maintainers who do not follow or enforce the Code of Conduct in good faith may face temporary or permanent repercussions as determined by other members of the project's leadership.
## Attribution
This Code of Conduct is adapted from the [Contributor Covenant][homepage], version 1.4, available at [https://contributor-covenant.org/version/1/4][version]
[homepage]: https://contributor-covenant.org
[version]: https://contributor-covenant.org/version/1/4/

144
.github/contributing.md vendored Normal file
View File

@@ -0,0 +1,144 @@
# Contributing to Marlin
Thanks for your interest in contributing to Marlin Firmware!
The following is a set of guidelines for contributing to Marlin, hosted by the [MarlinFirmware Organization](https://github.com/MarlinFirmware) on GitHub. These are mostly guidelines, not rules. Use your best judgment, and feel free to propose changes to this document in a Pull Request.
#### Table Of Contents
[Code of Conduct](#code-of-conduct)
[I don't want to read this whole thing, I just have a question!!!](#i-dont-want-to-read-this-whole-thing-i-just-have-a-question)
[How Can I Contribute?](#how-can-i-contribute)
* [Reporting Bugs](#reporting-bugs)
* [Suggesting Features or Changes](#suggesting-features-or-changes)
* [Your First Code Contribution](#your-first-code-contribution)
* [Pull Requests](#pull-requests)
[Styleguides](#styleguides)
* [Git Commit Messages](#git-commit-messages)
* [C++ Coding Standards](#c++-coding-standards)
* [Documentation Styleguide](#documentation)
[Additional Notes](#additional-notes)
* [Issue and Pull Request Labels](#issue-and-pull-request-labels)
## Code of Conduct
This project and everyone participating in it is governed by the [Marlin Code of Conduct](code_of_conduct.md). By participating, you are expected to uphold this code. Please report unacceptable behavior to [marlinfirmware@github.com](mailto:marlinfirmware@github.com).
## I don't want to read this whole thing I just have a question!!!
> **Note:** Please don't file an issue to ask a question. You'll get faster results by using the resources below.
We have a Message Board and a Facebook group where our knowledgable user community can provide helpful advice if you have questions.
* [Marlin RepRap forum](http://forums.reprap.org/list.php?415)
* [MarlinFirmware on Facebook](https://www.facebook.com/groups/1049718498464482/)
If chat is more your speed, you can join the MarlinFirmware Slack team:
* Join the Marlin Slack Team
* To obtain group access, please [send a request](http://www.thinkyhead.com/contact/9) to @thinkyhead.
* Even though Slack is a chat service, sometimes it takes several hours for community members to respond — please be patient!
* Use the `#general` channel for general questions or discussion about Marlin.
* Other channels exist for certain topics. Check the channel list.
## How Can I Contribute?
### Reporting Bugs
This section guides you through submitting a Bug Report for Marlin. Following these guidelines helps maintainers and the community understand your report, reproduce the behavior, and find related reports.
Before creating a Bug Report, please test the "nightly" development branch, as you might find out that you don't need to create one. When you are creating a Bug Report, please [include as many details as possible](#how-do-i-submit-a-good-bug-report). Fill out [the required template](issue_template.md), the information it asks for helps us resolve issues faster.
> **Note:** Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888.
#### How Do I Submit A (Good) Bug Report?
Bugs are tracked as [GitHub issues](https://guides.github.com/features/issues/). Use the New Issue button to create an issue and provide the following information by filling in [the template](issue_template.md).
Explain the problem and include additional details to help maintainers reproduce the problem:
* **Use a clear and descriptive title** for the issue to identify the problem.
* **Describe the exact steps which reproduce the problem** in as many details as possible. For example, start by explaining how you started Marlin, e.g. which command exactly you used in the terminal, or how you started Marlin otherwise. When listing steps, **don't just say what you did, but explain how you did it**. For example, if you moved the cursor to the end of a line, explain if you used the mouse, or a keyboard shortcut or an Marlin command, and if so which one?
* **Provide specific examples to demonstrate the steps**. Include links to files or GitHub projects, or copy/pasteable snippets, which you use in those examples. If you're providing snippets or log output in the issue, use [Markdown code blocks](https://help.github.com/articles/markdown-basics/#multiple-lines).
* **Describe the behavior you observed after following the steps** and point out what exactly is the problem with that behavior.
* **Explain which behavior you expected to see instead and why.**
* **Include detailed log output** especially for probing and leveling. See below for usage of `DEBUG_LEVELING_FEATURE`.
* **Include screenshots, links to videos, etc.** which clearly demonstrate the problem.
* **Include G-code** (if relevant) that reliably causes the problem to show itself.
* **If the problem wasn't triggered by a specific action**, describe what you were doing before the problem happened and share more information using the guidelines below.
Provide more context:
* **Can you reproduce the problem with a minimum of options enabled?**
* **Did the problem start happening recently** (e.g. after updating to a new version of Marlin) or was this always a problem?
* If the problem started happening recently, **can you reproduce the problem in an older version of Marlin?** What's the most recent version in which the problem doesn't happen? You can download older versions of Marlin from [the releases page](https://github.com/MarlinFirmware/Marlin/releases).
* **Can you reliably reproduce the issue?** If not, provide details about how often the problem happens and under which conditions it normally happens.
Include details about your configuration and environment:
* **Which version of Marlin are you using?** Marlin's exact version and build date can be seen in the startup message when a host connects to Marlin, or in the LCD Info menu (if enabled).
* **What kind of 3D Printer and electronics are you using**?
* **What kind of add-ons (probe, filament sensor) do you have**?
* **Include your Configuration files.** Make a ZIP file containing `Configuration.h` and `Configuration_adv.h` and drop it on your reply.
### Suggesting Features or Changes
This section guides you through submitting a suggestion for Marlin, including completely new features and minor improvements to existing functionality. Following these guidelines helps maintainers and the community understand your suggestion and find related suggestions.
Before creating a suggestion, please check [this list](#before-submitting-a-suggestion) as you might find out that you don't need to create one. When you are creating an enhancement suggestion, please [include as many details as possible](#how-do-i-submit-a-good-enhancement-suggestion). Fill in [the template](issue_template.md), including the steps that you imagine you would take if the feature you're requesting existed.
#### Before Submitting a Feature Request
* **Check the [Marlin website](http://marlinfw.org/)** for tips — you might discover that the feature is already included. Most importantly, check if you're using [the latest version of Marlin](https://github.com/MarlinFirmware/Marlin/releases) and if you can get the desired behavior by changing [Marlin's config settings](http://marlinfw.org/docs/configuration/configuration.html).
* **Perform a [cursory search](https://github.com/MarlinFirmware/Marlin/issues?q=is%3Aissue)** to see if the enhancement has already been suggested. If it has, add a comment to the existing issue instead of opening a new one.
#### How Do I Submit A (Good) Feature Request?
Feature Requests are tracked as [GitHub issues](https://guides.github.com/features/issues/). Please follow these guidelines in your request:
* **Use a clear and descriptive title** for the issue to identify the suggestion.
* **Provide a step-by-step description of the requested feature** in as much detail as possible.
* **Provide specific examples to demonstrate the steps**.
* **Describe the current behavior** and **explain which behavior you expected to see instead** and why.
* **Include screenshots and links to videos** which demonstrate the feature or point out the part of Marlin to which the request is related.
* **Explain why this feature would be useful** to most Marlin users.
* **Name other firmwares that have this feature, if any.**
### Your First Code Contribution
Unsure where to begin contributing to Marlin? You can start by looking through these `good-first-issue` and `help-wanted` issues:
* [Beginner issues][good-first-issue] - issues which should only require a few lines of code, and a test or two.
* [Help Wanted issues][help-wanted] - issues which should be a bit more involved than `beginner` issues.
### Pull Requests
Pull Requests should always be targeted to working branches (e.g., `bugfix-1.1.x` and/or `bugfix-2.0.x`) and never to release branches (e.g., `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](http://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
* Fill in [the required template](pull_request_template.md).
* Don't include issue numbers in the PR title.
* Include pictures, diagrams, and links to videos in your Pull Request to demonstrate your changes, if needed.
* Follow the [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) posted on our website.
* Document new code with clear and concise comments.
* End all files with a newline.
## Styleguides
### Git Commit Messages
* Use the present tense ("Add feature" not "Added feature").
* Use the imperative mood ("Move cursor to..." not "Moves cursor to...").
* Limit the first line to 72 characters or fewer.
* Reference issues and Pull Requests liberally after the first line.
### C++ Coding Standards
* Please read and follow the [Coding Standards](http://marlinfw.org/docs/development/coding_standards.html) posted on our website. Failure to follow these guidelines will delay evaluation and acceptance of Pull Requests.
### Documentation
* Guidelines for documentation are still under development. In-general, be clear, concise, and to-the-point.

View File

@@ -1,36 +1,31 @@
Thank you for submitting your feedback to the Marlin project.
Please use one of the templates below to fill out this box.
<!--
------------------------------------------------------------
### Feature Request
Please put [FR] in the issue title: `[FR] Add-on that goes 'ping'`
Have you read Marlin's Code of Conduct? By filing an Issue, you are expected to comply with it, including treating everyone with respect: https://github.com/MarlinFirmware/Marlin/blob/1.1.x/.github/code_of_conduct.md
------------------------------------------------------------
### Compile Error
When I compile with `FEATURE_X` I get an error:
```
Paste_the_error_text_here
```
Do you want to ask a question? Are you looking for support? Please don't post here. Instead please use the Marlin Firmware forum at http://forums.reprap.org/list.php?415 or the Marlin Facebook Group https://www.facebook.com/groups/1049718498464482/.
------------------------------------------------------------
### Bug Report
- Description: ---
- Expected behaviour: ---
- Actual behaviour: ---
- Steps to reproduce:
- Do this
- Do that
Before filing an issue be sure to test the 1.1 and/or 2.0 "bugfix" branches to see whether the issue is already addressed.
Attach a ZIP of `Configuration.h` and `Configuration_adv.h` by dropping here.
-->
------------------------------------------------------------
### Bug Report Tips
- When troubleshooting, use `M502` followed by `M500` to reset EEPROM to defaults.
- Use `DEBUG_LEVELING_FEATURE` with `M111 S247` for detailed logging of homing/leveling.
- Format text with: **bold**, _italic_, `code`.
- Format C++ with three backticks, plus "cpp":
```cpp
void my_function(bool do_it) {
// Hold this spot
}
```
### Description
<!-- Description of the bug or requested feature -->
### Steps to Reproduce
<!-- If this is a Bug Report, please describe the steps needed to reproduce the issue -->
1. [First Step]
2. [Second Step]
3. [and so on...]
**Expected behavior:** [What you expect to happen]
**Actual behavior:** [What actually happens]
#### Additional Information
* Include a ZIP file containing your `Configuration.h` and `Configuration_adv.h` files.
* Provide pictures or links to videos that clearly demonstrate the issue.
* See [How Can I Contribute](https://github.com/MarlinFirmware/Marlin/blob/1.1.x/.github/contributing.md#how-can-i-contribute) for additional guidelines.

19
.github/pull_request_template.md vendored Normal file
View File

@@ -0,0 +1,19 @@
### Requirements
* Filling out this template is required. Pull Requests without a clear description may be closed at the maintainers' discretion.
### Description
<!--
We must be able to understand your proposed change from this description. If we can't understand what the code will do from this description, the Pull Request may be closed at the maintainers' discretion. Keep in mind that the maintainer reviewing this PR may not be familiar with or have worked with the code recently, so please walk us through the concepts.
-->
### Benefits
<!-- What does this fix or improve? -->
### Related Issues
<!-- Whether this fixes a bug or fulfills a feature request, please list any related Issues here. -->

6
.gitignore vendored
View File

@@ -125,6 +125,7 @@ lib/readme.txt
#Visual Studio
*.sln
*.vcxproj
*.vcxproj.user
*.vcxproj.filters
Release/
Debug/
@@ -132,9 +133,12 @@ __vm/
.vs/
vc-fileutils.settings
#VScode
#Visual Studio Code
.vscode
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/*.db
#cmake
CMakeLists.txt

View File

@@ -22,10 +22,10 @@ before_install:
#
install:
#
# Install arduino 1.6.10
- wget http://downloads-02.arduino.cc/arduino-1.6.10-linux64.tar.xz
- tar xf arduino-1.6.10-linux64.tar.xz
- sudo mv arduino-1.6.10 /usr/local/share/arduino
# Install arduino 1.8.5
- wget http://downloads-02.arduino.cc/arduino-1.8.5-linux64.tar.xz
- tar xf arduino-1.8.5-linux64.tar.xz
- sudo mv arduino-1.8.5 /usr/local/share/arduino
- ln -s /usr/local/share/arduino/arduino ${TRAVIS_BUILD_DIR}/buildroot/bin/arduino
#
# Install: LiquidCrystal_I2C library
@@ -90,26 +90,37 @@ script:
- opt_set TEMP_SENSOR_0 -2
- opt_set TEMP_SENSOR_1 1
- opt_set TEMP_SENSOR_BED 1
- opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS
- opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_LED
- opt_set POWER_SUPPLY 1
- opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS PINS_DEBUGGING
- opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_LED AUTO_POWER_CONTROL NOZZLE_PARK_FEATURE FILAMENT_RUNOUT_SENSOR
- opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
- opt_enable_adv FWRETRACT MAX7219_DEBUG LED_CONTROL_MENU
- opt_set ABL_GRID_POINTS_X 16
- opt_set ABL_GRID_POINTS_Y 16
- opt_enable_adv ARC_P_CIRCLES ADVANCED_PAUSE_FEATURE CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE
- opt_enable_adv FWRETRACT MAX7219_DEBUG LED_CONTROL_MENU CASE_LIGHT_ENABLE CASE_LIGHT_USE_NEOPIXEL CODEPENDENT_XY_HOMING
- opt_set GRID_MAX_POINTS_X 16
- opt_set_adv FANMUX0_PIN 53
- build_marlin
#
# Test a probeless build of AUTO_BED_LEVELING_UBL
# Test a probeless build of AUTO_BED_LEVELING_UBL, with lots of extruders
#
- restore_configs
- opt_enable AUTO_BED_LEVELING_UBL DEBUG_LEVELING_FEATURE G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT EEPROM_SETTINGS EEPROM_CHITCHAT G3D_PANEL
- opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING NANODLP_Z_SYNC
- opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO
- opt_set EXTRUDERS 5
- opt_set TEMP_SENSOR_1 1
- opt_set TEMP_SENSOR_2 5
- opt_set TEMP_SENSOR_3 20
- opt_set TEMP_SENSOR_4 999
- opt_set TEMP_SENSOR_BED 1
- opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 DEBUG_LEVELING_FEATURE G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT SKEW_CORRECTION
- opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
- opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING BABYSTEP_XY LIN_ADVANCE NANODLP_Z_SYNC QUICK_HOME JUNCTION_DEVIATION MAX7219_DEBUG
- opt_set_adv MAX7219_ROTATE 270
- build_marlin
#
# Add a Sled Z Probe, use UBL Cartesian moves
# Add a Sled Z Probe, use UBL Cartesian moves, use Japanese language
#
- opt_enable Z_PROBE_SLED SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE
- opt_enable Z_PROBE_SLED SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE S_CURVE_ACCELERATION
- opt_set LCD_LANGUAGE kana_utf8
- opt_disable SEGMENT_LEVELED_MOVES
- opt_enable_adv BABYSTEP_ZPROBE_OFFSET DOUBLECLICK_FOR_Z_BABYSTEPPING
- build_marlin
@@ -118,7 +129,7 @@ script:
# ...with AUTO_BED_LEVELING_3POINT, DEBUG_LEVELING_FEATURE, EEPROM_SETTINGS, EEPROM_CHITCHAT, EXTENDED_CAPABILITIES_REPORT, and AUTO_REPORT_TEMPERATURES
#
- restore_configs
- opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
- opt_enable NUM_SERVOS Z_PROBE_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE
- opt_set NUM_SERVOS 1
- opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT
- opt_enable_adv NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET
@@ -134,8 +145,8 @@ script:
# PROBE_MANUALLY feature, with LCD support,
# ULTIMAKERCONTROLLER, FILAMENT_LCD_DISPLAY, FILAMENT_WIDTH_SENSOR,
# PRINTCOUNTER, NOZZLE_PARK_FEATURE, NOZZLE_CLEAN_FEATURE, PCA9632,
# Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS,
# ADVANCED_PAUSE_FEATURE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU,
# Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS,
# ADVANCED_PAUSE_FEATURE, ADVANCED_PAUSE_CONTINUOUS_PURGE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU, M114_DETAIL
# EEPROM_SETTINGS, EEPROM_CHITCHAT, M100_FREE_MEMORY_WATCHER,
# INCH_MODE_SUPPORT, TEMPERATURE_UNITS_SUPPORT
#
@@ -144,32 +155,20 @@ script:
- opt_enable PROBE_MANUALLY AUTO_BED_LEVELING_BILINEAR G26_MESH_EDITING LCD_BED_LEVELING ULTIMAKERCONTROLLER
- opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT M100_FREE_MEMORY_WATCHER M100_FREE_MEMORY_DUMPER M100_FREE_MEMORY_CORRUPTOR INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT
- opt_enable ULTIMAKERCONTROLLER SDSUPPORT
- opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632 USE_XMAX_PLUG
- opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632
- opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS
- opt_enable_adv ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU M114_DETAIL
- opt_enable_adv ADVANCED_PAUSE_FEATURE ADVANCED_PAUSE_CONTINUOUS_PURGE FILAMENT_LOAD_UNLOAD_GCODES PARK_HEAD_ON_PAUSE LCD_INFO_MENU M114_DETAIL
- opt_set_adv PWM_MOTOR_CURRENT {1300,1300,1250}
- opt_set_adv I2C_SLAVE_ADDRESS 63
- build_marlin
#
# Test 5 extruders on AZTEEG_X3_PRO (can use any board with >=5 extruders defined)
# Include a test for LIN_ADVANCE here also
#
- opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO
- opt_set EXTRUDERS 5
- opt_set TEMP_SENSOR_1 1
- opt_set TEMP_SENSOR_2 5
- opt_set TEMP_SENSOR_3 20
- opt_set TEMP_SENSOR_4 999
- opt_set TEMP_SENSOR_BED 1
- opt_enable_adv LIN_ADVANCE
- build_marlin
#
# Mixing Extruder with 5 steppers
# Mixing Extruder with 5 steppers, Cyrillic
#
- restore_configs
- opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO
- opt_enable MIXING_EXTRUDER
- opt_enable MIXING_EXTRUDER CR10_STOCKDISPLAY
- opt_set MIXING_STEPPERS 5
- opt_set LCD_LANGUAGE ru
- build_marlin
#
# Test DUAL_X_CARRIAGE
@@ -184,11 +183,11 @@ script:
#
# Test SPEAKER with BOARD_BQ_ZUM_MEGA_3D and BQ_LCD_SMART_CONTROLLER
#
- restore_configs
- opt_set MOTHERBOARD BOARD_BQ_ZUM_MEGA_3D
- opt_set LCD_FEEDBACK_FREQUENCY_DURATION_MS 10
- opt_set LCD_FEEDBACK_FREQUENCY_HZ 100
- opt_enable BQ_LCD_SMART_CONTROLLER SPEAKER
#- restore_configs
#- opt_set MOTHERBOARD BOARD_BQ_ZUM_MEGA_3D
#- opt_set LCD_FEEDBACK_FREQUENCY_DURATION_MS 10
#- opt_set LCD_FEEDBACK_FREQUENCY_HZ 100
#- opt_enable BQ_LCD_SMART_CONTROLLER SPEAKER
#
# Test SWITCHING_EXTRUDER
#
@@ -197,15 +196,14 @@ script:
- opt_set EXTRUDERS 2
- opt_enable NUM_SERVOS
- opt_set NUM_SERVOS 1
- opt_set TEMP_SENSOR_1 1
- opt_enable SWITCHING_EXTRUDER ULTIMAKERCONTROLLER
- build_marlin
#
# Enable COREXY
#
- restore_configs
- opt_enable COREXY
- build_marlin
#- restore_configs
#- opt_enable COREXY
#- build_marlin
#
# Test many less common options
#
@@ -219,7 +217,7 @@ script:
- opt_enable_adv VOLUMETRIC_DEFAULT_ON NO_WORKSPACE_OFFSETS ACTION_ON_KILL
- opt_enable_adv EXTRA_FAN_SPEED FWERETRACT Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS
- opt_enable_adv MENU_ADDAUTOSTART SDCARD_SORT_ALPHA
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT
- opt_enable FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR
- opt_enable ENDSTOP_INTERRUPTS_FEATURE FAN_SOFT_PWM SDSUPPORT
- opt_enable USE_XMAX_PLUG
@@ -229,15 +227,15 @@ script:
#
# ULTRA_LCD
#
- restore_configs
- opt_enable ULTRA_LCD
- build_marlin
#- restore_configs
#- opt_enable ULTRA_LCD
#- build_marlin
#
# DOGLCD
#
- restore_configs
- opt_enable DOGLCD
- build_marlin
#- restore_configs
#- opt_enable DOGLCD
#- build_marlin
#
# MAKRPANEL
# Needs to use Melzi and Sanguino hardware
@@ -248,29 +246,33 @@ script:
#
# REPRAP_DISCOUNT_SMART_CONTROLLER, SDSUPPORT, BABYSTEPPING, RIGIDBOARD_V2, and DAC_MOTOR_CURRENT_DEFAULT
#
- restore_configs
- opt_set MOTHERBOARD BOARD_RIGIDBOARD_V2
- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT
- build_marlin
#
#- restore_configs
#- opt_set MOTHERBOARD BOARD_RIGIDBOARD_V2
#- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT
#- build_marlin
# #
# G3D_PANEL with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING
#
#- restore_configs
#- opt_enable G3D_PANEL SDSUPPORT
#- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
#- opt_set_adv SDSORT_GCODE true
#- opt_set_adv SDSORT_USES_RAM true
#- opt_set_adv SDSORT_USES_STACK true
#- opt_set_adv SDSORT_CACHE_NAMES true
#- build_marlin
#
# REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER with LIGHTWEIGHT_UI
#
- restore_configs
- opt_enable G3D_PANEL SDSUPPORT
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES LIGHTWEIGHT_UI
- opt_set_adv SDSORT_GCODE true
- opt_set_adv SDSORT_USES_RAM true
- opt_set_adv SDSORT_USES_STACK true
- opt_set_adv SDSORT_CACHE_NAMES true
- build_marlin
#
# REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING
#
- restore_configs
- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
- opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING SCROLL_LONG_FILENAMES
- build_marlin
#
# REPRAPWORLD_KEYPAD
#
# Cant find configuration details to get it to compile
@@ -280,9 +282,9 @@ script:
#
# RA_CONTROL_PANEL
#
- restore_configs
- opt_enable RA_CONTROL_PANEL PINS_DEBUGGING
- build_marlin
#- restore_configs
#- opt_enable RA_CONTROL_PANEL PINS_DEBUGGING
#- build_marlin
#
######## I2C LCD/PANELS ##############
#
@@ -290,10 +292,10 @@ script:
# Most I2C configurations are failing at the moment because they require
# a different Liquid Crystal library "LiquidTWI2".
#
# LCD_I2C_SAINSMART_YWROBOT
# LCD_SAINSMART_I2C_1602
#
#- restore_configs
#- opt_enable LCD_I2C_SAINSMART_YWROBOT
#- opt_enable LCD_SAINSMART_I2C_1602
#- build_marlin
#
# LCD_I2C_PANELOLU2
@@ -310,9 +312,19 @@ script:
#
# LCM1602
#
- restore_configs
- opt_enable LCM1602
- build_marlin
#- restore_configs
#- opt_enable LCM1602
#- build_marlin
#
# Language files test with REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#
#- restore_configs
#- opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
#- for lang in an bg ca zh_CN zh_TW cz da de el el-gr en es eu fi fr gl hr it jp-kana nl pl pt pt-br ru sk tr uk test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; build_marlin
#
#- restore_configs
#- opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT
#- for lang in an bg ca zh_CN zh_TW cz da de el el-gr en es eu fi fr gl hr it jp-kana nl pl pt pt-br ru sk tr uk test; do opt_set LCD_LANGUAGE $lang; echo "compile with language $lang ..."; build_marlin
#
#
######## Example Configurations ##############
@@ -330,8 +342,8 @@ script:
# 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_UBL Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY
- opt_enable AUTO_BED_LEVELING_UBL RESTORE_LEVELING_AFTER_G28 Z_PROBE_ALLEN_KEY EEPROM_SETTINGS EEPROM_CHITCHAT
- opt_enable OLED_PANEL_TINYBOY2 MESH_EDIT_GFX_OVERLAY
- build_marlin
#
# Delta Config (FLSUN AC because it's complex)
@@ -348,14 +360,20 @@ script:
#
- use_example_configs SCARA
- opt_enable AUTO_BED_LEVELING_BILINEAR FIX_MOUNTED_PROBE USE_ZMIN_PLUG EEPROM_SETTINGS EEPROM_CHITCHAT ULTIMAKERCONTROLLER
- opt_enable_adv HAVE_TMC2130 X_IS_TMC2130 Y_IS_TMC2130 Z_IS_TMC2130
- opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD TMC_DEBUG SENSORLESS_HOMING
- opt_set X_DRIVER_TYPE TMC2130
- opt_set Y_DRIVER_TYPE TMC2130
- opt_set Z_DRIVER_TYPE TMC2130
- opt_set E0_DRIVER_TYPE TMC2130
- opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD SENSORLESS_HOMING
- build_marlin
#
# TMC2208 Config
#
- restore_configs
- opt_enable_adv HAVE_TMC2208 X_IS_TMC2208 Y_IS_TMC2208 Z_IS_TMC2208
- opt_set X_DRIVER_TYPE TMC2208
- opt_set Y_DRIVER_TYPE TMC2208
- opt_set Z_DRIVER_TYPE TMC2208
- opt_set E0_DRIVER_TYPE TMC2208
- opt_enable_adv MONITOR_DRIVER_STATUS STEALTHCHOP HYBRID_THRESHOLD TMC_DEBUG
- build_marlin
#

View File

@@ -28,451 +28,501 @@
#ifndef CONDITIONALS_LCD_H // Get the LCD defines which are needed first
#define CONDITIONALS_LCD_H
#define LCD_HAS_DIRECTIONAL_BUTTONS (BUTTON_EXISTS(UP) || BUTTON_EXISTS(DWN) || BUTTON_EXISTS(LFT) || BUTTON_EXISTS(RT))
#define LCD_HAS_DIRECTIONAL_BUTTONS (BUTTON_EXISTS(UP) || BUTTON_EXISTS(DWN) || BUTTON_EXISTS(LFT) || BUTTON_EXISTS(RT))
#if ENABLED(CARTESIO_UI)
#if ENABLED(CARTESIO_UI)
#define DOGLCD
#define ULTIPANEL
#define DEFAULT_LCD_CONTRAST 90
#define LCD_CONTRAST_MIN 60
#define LCD_CONTRAST_MAX 140
#define DOGLCD
#define ULTIPANEL
#define DEFAULT_LCD_CONTRAST 90
#define LCD_CONTRAST_MIN 60
#define LCD_CONTRAST_MAX 140
#elif ENABLED(MAKRPANEL)
#elif ENABLED(MAKRPANEL)
#define U8GLIB_ST7565_64128N
#elif ENABLED(ZONESTAR_LCD)
#define REPRAPWORLD_KEYPAD
#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
#define ADC_KEYPAD
#define ADC_KEY_NUM 8
#define ULTIPANEL
// this helps to implement ADC_KEYPAD menus
#define ENCODER_PULSES_PER_STEP 1
#define ENCODER_STEPS_PER_MENU_ITEM 1
#define ENCODER_FEEDRATE_DEADZONE 2
#define REVERSE_MENU_DIRECTION
#elif ENABLED(ANET_FULL_GRAPHICS_LCD)
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#elif ENABLED(BQ_LCD_SMART_CONTROLLER)
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#elif ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define ULTRA_LCD //general LCD support, also 16x2
#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
#if ENABLED(miniVIKI)
#define LCD_CONTRAST_MIN 75
#define LCD_CONTRAST_MAX 115
#define DEFAULT_LCD_CONTRAST 95
#define U8GLIB_ST7565_64128N
#elif ENABLED(ZONESTAR_LCD)
#define REPRAPWORLD_KEYPAD
#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
#define ADC_KEYPAD
#define ADC_KEY_NUM 8
#define ULTIPANEL
// this helps to implement ADC_KEYPAD menus
#define ENCODER_PULSES_PER_STEP 1
#define ENCODER_STEPS_PER_MENU_ITEM 1
#define ENCODER_FEEDRATE_DEADZONE 2
#define REVERSE_MENU_DIRECTION
#elif ENABLED(ANET_FULL_GRAPHICS_LCD)
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#elif ENABLED(BQ_LCD_SMART_CONTROLLER)
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#elif ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define ULTRA_LCD //general LCD support, also 16x2
#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
#if ENABLED(miniVIKI)
#define LCD_CONTRAST_MIN 75
#define LCD_CONTRAST_MAX 115
#define DEFAULT_LCD_CONTRAST 95
#define U8GLIB_ST7565_64128N
#elif ENABLED(VIKI2)
#define LCD_CONTRAST_MIN 0
#define LCD_CONTRAST_MAX 255
#define DEFAULT_LCD_CONTRAST 140
#define U8GLIB_ST7565_64128N
#elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define LCD_CONTRAST_MIN 90
#define LCD_CONTRAST_MAX 130
#define DEFAULT_LCD_CONTRAST 110
#define U8GLIB_LM6059_AF
#define SD_DETECT_INVERTED
#endif
#elif ENABLED(OLED_PANEL_TINYBOY2)
#define U8GLIB_SSD1306
#define ULTIPANEL
#define REVERSE_ENCODER_DIRECTION
#define REVERSE_MENU_DIRECTION
#elif ENABLED(RA_CONTROL_PANEL)
#define LCD_I2C_TYPE_PCA8574
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#define ULTIPANEL
#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#define DOGLCD
#define U8GLIB_ST7920
#define ULTIPANEL
#elif ENABLED(CR10_STOCKDISPLAY)
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#ifndef ST7920_DELAY_1
#define ST7920_DELAY_1 DELAY_2_NOP
#endif
#ifndef ST7920_DELAY_2
#define ST7920_DELAY_2 DELAY_2_NOP
#endif
#ifndef ST7920_DELAY_3
#define ST7920_DELAY_3 DELAY_2_NOP
#endif
#elif ENABLED(MKS_12864OLED)
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#define U8GLIB_SH1106
#elif ENABLED(MKS_12864OLED_SSD1306)
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#define U8GLIB_SSD1306
#elif ENABLED(MKS_MINI_12864)
#define MINIPANEL
#elif ENABLED(VIKI2)
#define LCD_CONTRAST_MIN 0
#define LCD_CONTRAST_MAX 255
#define DEFAULT_LCD_CONTRAST 140
#define U8GLIB_ST7565_64128N
#elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define LCD_CONTRAST_MIN 90
#define LCD_CONTRAST_MAX 130
#define DEFAULT_LCD_CONTRAST 110
#define U8GLIB_LM6059_AF
#define SD_DETECT_INVERTED
#endif
#if ENABLED(MAKRPANEL) || ENABLED(MINIPANEL)
#define DOGLCD
#define ULTIPANEL
#define DEFAULT_LCD_CONTRAST 17
#elif ENABLED(OLED_PANEL_TINYBOY2)
#define U8GLIB_SSD1306
#define ULTIPANEL
#define REVERSE_ENCODER_DIRECTION
#define REVERSE_MENU_DIRECTION
#elif ENABLED(RA_CONTROL_PANEL)
#define LCD_I2C_TYPE_PCA8574
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#define ULTIPANEL
#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD)
#define DOGLCD
#define U8GLIB_ST7920
#define ULTIPANEL
#elif ENABLED(CR10_STOCKDISPLAY)
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
#ifndef ST7920_DELAY_1
#define ST7920_DELAY_1 DELAY_NS(125)
#endif
#ifndef ST7920_DELAY_2
#define ST7920_DELAY_2 DELAY_NS(125)
#endif
#ifndef ST7920_DELAY_3
#define ST7920_DELAY_3 DELAY_NS(125)
#endif
// Generic support for SSD1306 / SH1106 OLED based LCDs.
#if ENABLED(U8GLIB_SSD1306) || ENABLED(U8GLIB_SH1106)
#define ULTRA_LCD //general LCD support, also 16x2
#define DOGLCD // Support for I2C LCD 128x64 (Controller SSD1306 / SH1106 graphic Display Family)
#elif ENABLED(MKS_12864OLED)
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#define U8GLIB_SH1106
#elif ENABLED(MKS_12864OLED_SSD1306)
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#define U8GLIB_SSD1306
#elif ENABLED(MKS_MINI_12864)
#define MINIPANEL
#endif
#if ENABLED(MAKRPANEL) || ENABLED(MINIPANEL)
#define DOGLCD
#define ULTIPANEL
#define DEFAULT_LCD_CONTRAST 17
#endif
#if ENABLED(ULTI_CONTROLLER)
#define U8GLIB_SSD1309
#define REVERSE_ENCODER_DIRECTION
#define LCD_RESET_PIN LCD_PINS_D6 // This controller need a reset pin
#define LCD_CONTRAST_MIN 0
#define LCD_CONTRAST_MAX 254
#define DEFAULT_LCD_CONTRAST 127
#define ENCODER_PULSES_PER_STEP 2
#define ENCODER_STEPS_PER_MENU_ITEM 2
#endif
// Generic support for SSD1306 / SSD1309 / SH1106 OLED based LCDs.
#if ENABLED(U8GLIB_SSD1306) || ENABLED(U8GLIB_SSD1309) || ENABLED(U8GLIB_SH1106)
#define ULTRA_LCD //general LCD support, also 16x2
#define DOGLCD // Support for I2C LCD 128x64 (Controller SSD1306 / SSD1309 / SH1106 graphic Display Family)
#endif
#if ENABLED(PANEL_ONE) || ENABLED(U8GLIB_SH1106)
#define ULTIMAKERCONTROLLER
#elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602)
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#define LCD_WIDTH 16
#define LCD_HEIGHT 2
#endif
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI) || ENABLED(SILVER_GATE_GLCD_CONTROLLER)
#define DOGLCD
#define U8GLIB_ST7920
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#endif
#if ENABLED(ULTIMAKERCONTROLLER) \
|| ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \
|| ENABLED(G3D_PANEL) \
|| ENABLED(RIGIDBOT_PANEL) \
|| ENABLED(ULTI_CONTROLLER)
#define ULTIPANEL
#endif
#if ENABLED(REPRAPWORLD_KEYPAD)
#define NEWPANEL
#if ENABLED(ULTIPANEL) && !defined(REPRAPWORLD_KEYPAD_MOVE_STEP)
#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
#endif
#endif
/**
* I2C PANELS
*/
#if ENABLED(LCD_SAINSMART_I2C_1602) || ENABLED(LCD_SAINSMART_I2C_2004)
#define LCD_I2C_TYPE_PCF8575
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#define ULTRA_LCD
#if ENABLED(LCD_SAINSMART_I2C_2004)
#define LCD_WIDTH 20
#define LCD_HEIGHT 4
#endif
#if ENABLED(PANEL_ONE) || ENABLED(U8GLIB_SH1106)
#elif ENABLED(LCD_I2C_PANELOLU2)
#define ULTIMAKERCONTROLLER
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
#elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602)
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (optional)
#define ULTIPANEL
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#define LCD_WIDTH 16
#define LCD_HEIGHT 2
#endif
#if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI) || ENABLED(SILVER_GATE_GLCD_CONTROLLER)
#define DOGLCD
#define U8GLIB_ST7920
#define REPRAP_DISCOUNT_SMART_CONTROLLER
#endif
#if ENABLED(ULTIMAKERCONTROLLER) \
|| ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) \
|| ENABLED(G3D_PANEL) \
|| ENABLED(RIGIDBOT_PANEL)
#define ULTIPANEL
#endif
#if ENABLED(REPRAPWORLD_KEYPAD)
#define NEWPANEL
#if ENABLED(ULTIPANEL) && !defined(REPRAPWORLD_KEYPAD_MOVE_STEP)
#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
#endif
#endif
#elif ENABLED(LCD_I2C_VIKI)
/**
* I2C PANELS
* Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
*
* This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
* Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
* Note: The pause/stop/resume LCD button pin should be connected to the Arduino
* BTN_ENC pin (or set BTN_ENC to -1 if not used)
*/
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
#define ULTIPANEL
#if ENABLED(LCD_I2C_SAINSMART_YWROBOT)
#define ENCODER_FEEDRATE_DEADZONE 4
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
#define STD_ENCODER_PULSES_PER_STEP 1
#define STD_ENCODER_STEPS_PER_MENU_ITEM 2
#define LCD_I2C_TYPE_PCF8575
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
#define ULTIPANEL
#elif ENABLED(G3D_PANEL)
#elif ENABLED(LCD_I2C_PANELOLU2)
#define STD_ENCODER_PULSES_PER_STEP 2
#define STD_ENCODER_STEPS_PER_MENU_ITEM 1
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
#elif ENABLED(miniVIKI) || ENABLED(VIKI2) \
|| ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
|| ENABLED(OLED_PANEL_TINYBOY2) \
|| ENABLED(BQ_LCD_SMART_CONTROLLER) \
|| ENABLED(LCD_I2C_PANELOLU2) \
|| ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
#define STD_ENCODER_PULSES_PER_STEP 4
#define STD_ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD
#define ULTIPANEL
#ifndef STD_ENCODER_PULSES_PER_STEP
#define STD_ENCODER_PULSES_PER_STEP 5
#endif
#ifndef STD_ENCODER_STEPS_PER_MENU_ITEM
#define STD_ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#ifndef ENCODER_PULSES_PER_STEP
#define ENCODER_PULSES_PER_STEP STD_ENCODER_PULSES_PER_STEP
#endif
#ifndef ENCODER_STEPS_PER_MENU_ITEM
#define ENCODER_STEPS_PER_MENU_ITEM STD_ENCODER_STEPS_PER_MENU_ITEM
#endif
#ifndef ENCODER_FEEDRATE_DEADZONE
#define ENCODER_FEEDRATE_DEADZONE 6
#endif
#elif ENABLED(LCD_I2C_VIKI)
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
/**
* Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
*
* This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 )
* Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory.
* Note: The pause/stop/resume LCD button pin should be connected to the Arduino
* BTN_ENC pin (or set BTN_ENC to -1 if not used)
*/
#define LCD_I2C_TYPE_MCP23017
#define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander
#define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later)
#define ULTIPANEL
#if ENABLED(SAV_3DLCD)
#define SR_LCD_2W_NL // Non latching 2 wire shift register
#define ULTIPANEL
#endif
#define ENCODER_FEEDRATE_DEADZONE 4
#define STD_ENCODER_PULSES_PER_STEP 1
#define STD_ENCODER_STEPS_PER_MENU_ITEM 2
#elif ENABLED(G3D_PANEL)
#define STD_ENCODER_PULSES_PER_STEP 2
#define STD_ENCODER_STEPS_PER_MENU_ITEM 1
#elif ENABLED(miniVIKI) || ENABLED(VIKI2) \
|| ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
|| ENABLED(OLED_PANEL_TINYBOY2) \
|| ENABLED(BQ_LCD_SMART_CONTROLLER) \
|| ENABLED(LCD_I2C_PANELOLU2) \
|| ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER)
#define STD_ENCODER_PULSES_PER_STEP 4
#define STD_ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#ifndef STD_ENCODER_PULSES_PER_STEP
#define STD_ENCODER_PULSES_PER_STEP 5
#endif
#ifndef STD_ENCODER_STEPS_PER_MENU_ITEM
#define STD_ENCODER_STEPS_PER_MENU_ITEM 1
#endif
#ifndef ENCODER_PULSES_PER_STEP
#define ENCODER_PULSES_PER_STEP STD_ENCODER_PULSES_PER_STEP
#endif
#ifndef ENCODER_STEPS_PER_MENU_ITEM
#define ENCODER_STEPS_PER_MENU_ITEM STD_ENCODER_STEPS_PER_MENU_ITEM
#endif
#ifndef ENCODER_FEEDRATE_DEADZONE
#define ENCODER_FEEDRATE_DEADZONE 6
#endif
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
#if ENABLED(SAV_3DLCD)
#define SR_LCD_2W_NL // Non latching 2 wire shift register
#define ULTIPANEL
#endif
#if ENABLED(DOGLCD) // Change number of lines to match the DOG graphic display
#ifndef LCD_WIDTH
#if ENABLED(DOGLCD) // Change number of lines to match the DOG graphic display
#ifndef LCD_WIDTH
#ifdef LCD_WIDTH_OVERRIDE
#define LCD_WIDTH LCD_WIDTH_OVERRIDE
#else
#define LCD_WIDTH 22
#endif
#ifndef LCD_HEIGHT
#define LCD_HEIGHT 5
#endif
#ifndef LCD_HEIGHT
#define LCD_HEIGHT 5
#endif
#endif
#if ENABLED(NO_LCD_MENUS)
#undef ULTIPANEL
#endif
#if ENABLED(ULTIPANEL)
#define NEWPANEL // Disable this if you actually have no click-encoder panel
#define ULTRA_LCD
#ifndef LCD_WIDTH
#define LCD_WIDTH 20
#endif
#ifndef LCD_HEIGHT
#define LCD_HEIGHT 4
#endif
#elif ENABLED(ULTRA_LCD) // no panel but just LCD
#ifndef LCD_WIDTH
#define LCD_WIDTH 16
#endif
#ifndef LCD_HEIGHT
#define LCD_HEIGHT 2
#endif
#endif
#if ENABLED(DOGLCD)
/* Custom characters defined in font dogm_font_data_Marlin_symbols.h / Marlin_symbols.fon */
// \x00 intentionally skipped to avoid problems in strings
#define LCD_STR_REFRESH "\x01"
#define LCD_STR_FOLDER "\x02"
#define LCD_STR_ARROW_RIGHT "\x03"
#define LCD_STR_UPLEVEL "\x04"
#define LCD_STR_CLOCK "\x05"
#define LCD_STR_FEEDRATE "\x06"
#define LCD_STR_BEDTEMP "\x07"
#define LCD_STR_THERMOMETER "\x08"
#define LCD_STR_DEGREE "\x09"
#define LCD_STR_SPECIAL_MAX '\x09'
// Maximum here is 0x1F because 0x20 is ' ' (space) and the normal charsets begin.
// Better stay below 0x10 because DISPLAY_CHARSET_HD44780_WESTERN begins here.
// Symbol characters
#define LCD_STR_FILAM_DIA "\xf8"
#define LCD_STR_FILAM_MUL "\xa4"
#else
// Custom characters defined in the first 8 characters of the LCD
#define LCD_BEDTEMP_CHAR 0x00 // Print only as a char. This will have 'unexpected' results when used in a string!
#define LCD_DEGREE_CHAR 0x01
#define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation
#define LCD_UPLEVEL_CHAR 0x03
#define LCD_STR_REFRESH "\x04"
#define LCD_STR_FOLDER "\x05"
#define LCD_FEEDRATE_CHAR 0x06
#define LCD_CLOCK_CHAR 0x07
#define LCD_STR_ARROW_RIGHT ">" /* from the default character set */
#endif
/**
* Default LCD contrast for dogm-like LCD displays
*/
#if ENABLED(DOGLCD)
#define HAS_LCD_CONTRAST ( \
ENABLED(MAKRPANEL) \
|| ENABLED(CARTESIO_UI) \
|| ENABLED(VIKI2) \
|| ENABLED(miniVIKI) \
|| ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
)
#if HAS_LCD_CONTRAST
#ifndef LCD_CONTRAST_MIN
#define LCD_CONTRAST_MIN 0
#endif
#ifndef LCD_CONTRAST_MAX
#define LCD_CONTRAST_MAX 63
#endif
#ifndef DEFAULT_LCD_CONTRAST
#define DEFAULT_LCD_CONTRAST 32
#endif
#endif
#endif
#if ENABLED(ULTIPANEL)
#define NEWPANEL // Disable this if you actually have no click-encoder panel
#define ULTRA_LCD
#ifndef LCD_WIDTH
#define LCD_WIDTH 20
#endif
#ifndef LCD_HEIGHT
#define LCD_HEIGHT 4
#endif
#elif ENABLED(ULTRA_LCD) // no panel but just LCD
#ifndef LCD_WIDTH
#define LCD_WIDTH 16
#endif
#ifndef LCD_HEIGHT
#define LCD_HEIGHT 2
#endif
#endif
// Boot screens
#if DISABLED(ULTRA_LCD)
#undef SHOW_BOOTSCREEN
#elif !defined(BOOTSCREEN_TIMEOUT)
#define BOOTSCREEN_TIMEOUT 2500
#endif
#if ENABLED(DOGLCD)
/* Custom characters defined in font dogm_font_data_Marlin_symbols.h / Marlin_symbols.fon */
// \x00 intentionally skipped to avoid problems in strings
#define LCD_STR_REFRESH "\x01"
#define LCD_STR_FOLDER "\x02"
#define LCD_STR_ARROW_RIGHT "\x03"
#define LCD_STR_UPLEVEL "\x04"
#define LCD_STR_CLOCK "\x05"
#define LCD_STR_FEEDRATE "\x06"
#define LCD_STR_BEDTEMP "\x07"
#define LCD_STR_THERMOMETER "\x08"
#define LCD_STR_DEGREE "\x09"
#define HAS_DEBUG_MENU (ENABLED(ULTIPANEL) && ENABLED(LCD_PROGRESS_BAR_TEST))
#define LCD_STR_SPECIAL_MAX '\x09'
// Maximum here is 0x1F because 0x20 is ' ' (space) and the normal charsets begin.
// Better stay below 0x10 because DISPLAY_CHARSET_HD44780_WESTERN begins here.
// Symbol characters
#define LCD_STR_FILAM_DIA "\xf8"
#define LCD_STR_FILAM_MUL "\xa4"
/**
* Extruders have some combination of stepper motors and hotends
* so we separate these concepts into the defines:
*
* EXTRUDERS - Number of Selectable Tools
* HOTENDS - Number of hotends, whether connected or separate
* E_STEPPERS - Number of actual E stepper motors
* E_MANUAL - Number of E steppers for LCD move options
*
*/
#if ENABLED(SWITCHING_EXTRUDER) // One stepper for every two EXTRUDERS
#if EXTRUDERS > 4
#define E_STEPPERS 3
#elif EXTRUDERS > 2
#define E_STEPPERS 2
#else
// Custom characters defined in the first 8 characters of the LCD
#define LCD_BEDTEMP_CHAR 0x00 // Print only as a char. This will have 'unexpected' results when used in a string!
#define LCD_DEGREE_CHAR 0x01
#define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation
#define LCD_UPLEVEL_CHAR 0x03
#define LCD_STR_REFRESH "\x04"
#define LCD_STR_FOLDER "\x05"
#define LCD_FEEDRATE_CHAR 0x06
#define LCD_CLOCK_CHAR 0x07
#define LCD_STR_ARROW_RIGHT ">" /* from the default character set */
#define E_STEPPERS 1
#endif
/**
* Default LCD contrast for dogm-like LCD displays
*/
#if ENABLED(DOGLCD)
#define HAS_LCD_CONTRAST ( \
ENABLED(MAKRPANEL) \
|| ENABLED(CARTESIO_UI) \
|| ENABLED(VIKI2) \
|| ENABLED(miniVIKI) \
|| ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) \
)
#if HAS_LCD_CONTRAST
#ifndef LCD_CONTRAST_MIN
#define LCD_CONTRAST_MIN 0
#endif
#ifndef LCD_CONTRAST_MAX
#define LCD_CONTRAST_MAX 63
#endif
#ifndef DEFAULT_LCD_CONTRAST
#define DEFAULT_LCD_CONTRAST 32
#endif
#endif
#if DISABLED(SWITCHING_NOZZLE)
#define HOTENDS E_STEPPERS
#endif
#define E_MANUAL EXTRUDERS
#elif ENABLED(MIXING_EXTRUDER)
#define E_STEPPERS MIXING_STEPPERS
#define E_MANUAL 1
#else
#define E_STEPPERS EXTRUDERS
#define E_MANUAL EXTRUDERS
#endif
// Boot screens
#if DISABLED(ULTRA_LCD)
#undef SHOW_BOOTSCREEN
#elif !defined(BOOTSCREEN_TIMEOUT)
#define BOOTSCREEN_TIMEOUT 2500
#endif
// No inactive extruders with MK2_MULTIPLEXER or SWITCHING_NOZZLE
#if ENABLED(MK2_MULTIPLEXER) || ENABLED(SWITCHING_NOZZLE)
#undef DISABLE_INACTIVE_EXTRUDER
#endif
#define HAS_DEBUG_MENU ENABLED(LCD_PROGRESS_BAR_TEST)
// MK2 Multiplexer forces SINGLENOZZLE
#if ENABLED(MK2_MULTIPLEXER)
#define SINGLENOZZLE
#endif
// MK2 Multiplexer forces SINGLENOZZLE to be enabled
#if ENABLED(MK2_MULTIPLEXER)
#define SINGLENOZZLE
#endif
#if ENABLED(SINGLENOZZLE) || ENABLED(MIXING_EXTRUDER) // One hotend, one thermistor, no XY offset
#undef HOTENDS
#define HOTENDS 1
#undef TEMP_SENSOR_1_AS_REDUNDANT
#undef HOTEND_OFFSET_X
#undef HOTEND_OFFSET_Y
#endif
/**
* Extruders have some combination of stepper motors and hotends
* so we separate these concepts into the defines:
*
* EXTRUDERS - Number of Selectable Tools
* HOTENDS - Number of hotends, whether connected or separate
* E_STEPPERS - Number of actual E stepper motors
* E_MANUAL - Number of E steppers for LCD move options
* TOOL_E_INDEX - Index to use when getting/setting the tool state
*
*/
#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
#else // Two hotends
#define HOTENDS EXTRUDERS
#if ENABLED(SWITCHING_NOZZLE) && !defined(HOTEND_OFFSET_Z)
#define HOTEND_OFFSET_Z { 0 }
#endif
#endif
#ifndef HOTENDS
#define HOTENDS EXTRUDERS
#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
#define DO_SWITCH_EXTRUDER (ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR))
/**
* DISTINCT_E_FACTORS affects how some E factors are accessed
*/
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
#define XYZE_N (XYZ + E_STEPPERS)
#if ENABLED(HANGPRINTER)
#define NUM_AXIS_N (ABCD + E_STEPPERS)
#else
#define E_STEPPERS EXTRUDERS
#define E_MANUAL EXTRUDERS
#define TOOL_E_INDEX current_block->active_extruder
#define NUM_AXIS_N (XYZ + E_STEPPERS)
#endif
/**
* DISTINCT_E_FACTORS affects how some E factors are accessed
*/
#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1
#define XYZE_N (XYZ + E_STEPPERS)
#define E_AXIS_N (E_AXIS + extruder)
#define E_AXIS_N (E_AXIS + extruder)
#else
#undef DISTINCT_E_FACTORS
#define XYZE_N XYZE
#if ENABLED(HANGPRINTER)
#define NUM_AXIS_N ABCDE
#else
#undef DISTINCT_E_FACTORS
#define XYZE_N XYZE
#define E_AXIS_N E_AXIS
#define NUM_AXIS_N XYZE
#endif
#define E_AXIS_N E_AXIS
#endif
/**
* The BLTouch Probe emulates a servo probe
* and uses "special" angles for its state.
*/
#if ENABLED(BLTOUCH)
#ifndef Z_ENDSTOP_SERVO_NR
#define Z_ENDSTOP_SERVO_NR 0
#endif
#ifndef NUM_SERVOS
#define NUM_SERVOS (Z_ENDSTOP_SERVO_NR + 1)
#endif
#undef DEACTIVATE_SERVOS_AFTER_MOVE
#if NUM_SERVOS == 1
#undef SERVO_DELAY
#define SERVO_DELAY { 50 }
#endif
#ifndef BLTOUCH_DELAY
#define BLTOUCH_DELAY 375
#endif
#undef Z_SERVO_ANGLES
#define Z_SERVO_ANGLES { BLTOUCH_DEPLOY, BLTOUCH_STOW }
#define BLTOUCH_DEPLOY 10
#define BLTOUCH_STOW 90
#define BLTOUCH_SELFTEST 120
#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
#define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN)
#else
#define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN_PROBE)
#endif
/**
* The BLTouch Probe emulates a servo probe
* and uses "special" angles for its state.
*/
#if ENABLED(BLTOUCH)
#ifndef Z_PROBE_SERVO_NR
#define Z_PROBE_SERVO_NR 0
#endif
/**
* Set a flag for a servo probe
*/
#define HAS_Z_SERVO_ENDSTOP (defined(Z_ENDSTOP_SERVO_NR) && Z_ENDSTOP_SERVO_NR >= 0)
/**
* Set a flag for any enabled probe
*/
#define PROBE_SELECTED (ENABLED(PROBE_MANUALLY) || ENABLED(FIX_MOUNTED_PROBE) || ENABLED(Z_PROBE_ALLEN_KEY) || HAS_Z_SERVO_ENDSTOP || ENABLED(Z_PROBE_SLED) || ENABLED(SOLENOID_PROBE))
/**
* Clear probe pin settings when no probe is selected
*/
#if !PROBE_SELECTED || ENABLED(PROBE_MANUALLY)
#undef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
#undef Z_MIN_PROBE_ENDSTOP
#ifndef NUM_SERVOS
#define NUM_SERVOS (Z_PROBE_SERVO_NR + 1)
#endif
#undef DEACTIVATE_SERVOS_AFTER_MOVE
#if NUM_SERVOS == 1
#undef SERVO_DELAY
#define SERVO_DELAY { 50 }
#endif
#ifndef BLTOUCH_DELAY
#define BLTOUCH_DELAY 375
#endif
#undef Z_SERVO_ANGLES
#define Z_SERVO_ANGLES { BLTOUCH_DEPLOY, BLTOUCH_STOW }
#define HAS_SOFTWARE_ENDSTOPS (ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS))
#define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER))
#define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED))
#define BLTOUCH_DEPLOY 10
#define BLTOUCH_STOW 90
#define BLTOUCH_SELFTEST 120
#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 Z_MIN_PROBE_ENDSTOP_INVERTING
#define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN)
#else
#define TEST_BLTOUCH() _TEST_BLTOUCH(Z_MIN_PROBE)
#endif
#endif
/**
* Set a flag for a servo probe
*/
#define HAS_Z_SERVO_PROBE (defined(Z_PROBE_SERVO_NR) && Z_PROBE_SERVO_NR >= 0)
/**
* Set flags for enabled probes
*/
#define HAS_BED_PROBE (ENABLED(FIX_MOUNTED_PROBE) || ENABLED(Z_PROBE_ALLEN_KEY) || HAS_Z_SERVO_PROBE || ENABLED(Z_PROBE_SLED) || ENABLED(SOLENOID_PROBE))
#define PROBE_SELECTED (HAS_BED_PROBE || ENABLED(PROBE_MANUALLY) || ENABLED(MESH_BED_LEVELING))
#if !HAS_BED_PROBE
// Clear probe pin settings when no probe is selected
#undef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN
#undef Z_MIN_PROBE_ENDSTOP
#elif ENABLED(Z_PROBE_ALLEN_KEY)
// Extra test for Allen Key Probe
#define PROBE_IS_TRIGGERED_WHEN_STOWED_TEST
#endif
#define HOMING_Z_WITH_PROBE (HAS_BED_PROBE && Z_HOME_DIR < 0 && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN))
#define HAS_SOFTWARE_ENDSTOPS (ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS))
#define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER))
#define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED))
#define USE_MARLINSERIAL !(defined(__AVR__) && defined(USBCON))
#endif // CONDITIONALS_LCD_H

File diff suppressed because it is too large Load Diff

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -69,6 +69,13 @@
// example_configurations/SCARA and customize for your machine.
//
//===========================================================================
//============================= HANGPRINTER =================================
//===========================================================================
// For a Hangprinter start with the configuration file in the
// example_configurations/hangprinter directory and customize for your machine.
//
// @section info
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
@@ -79,22 +86,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
//#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -196,11 +208,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -232,6 +244,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -245,6 +266,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -253,7 +275,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -263,6 +286,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -284,7 +308,7 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@@ -292,6 +316,7 @@
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 0
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -341,7 +366,7 @@
#define PIDTEMP
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -355,42 +380,49 @@
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114
// MakerGear
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
// Mendel Parts V9 on 12V
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
//#define PIDTEMPBED
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -399,30 +431,35 @@
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
@@ -477,11 +514,10 @@
//#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -500,10 +536,53 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -571,6 +650,16 @@
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -621,6 +710,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -631,7 +721,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -650,6 +740,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -687,13 +780,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER 10 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -717,6 +813,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 5 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -752,9 +852,6 @@
#define INVERT_Y_DIR true
#define INVERT_Z_DIR false
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -768,6 +865,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -800,7 +899,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -808,7 +907,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -816,18 +915,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -875,6 +979,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -897,12 +1007,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -914,13 +1024,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -943,17 +1050,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -962,27 +1058,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -991,8 +1083,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
//#define PROBE_PT_1_X 15
//#define PROBE_PT_1_Y 180
//#define PROBE_PT_2_X 15
//#define PROBE_PT_2_Y 20
//#define PROBE_PT_3_X 170
//#define PROBE_PT_3_Y 20
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -1004,6 +1109,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
//#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1277,11 +1387,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1309,19 +1419,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1348,19 +1445,28 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
// This option overrides the default number of encoder pulses needed to
// produce one step. Should be increased for high-resolution encoders.
//
//#define ENCODER_PULSES_PER_STEP 1
//#define ENCODER_PULSES_PER_STEP 4
//
// Use this option to override the number of step signals required to
// move between next/prev menu items.
//
//#define ENCODER_STEPS_PER_MENU_ITEM 5
//#define ENCODER_STEPS_PER_MENU_ITEM 1
/**
* Encoder Direction Options
@@ -1409,15 +1515,21 @@
// Note: Test audio output with the G-Code:
// M300 S<frequency Hz> P<duration ms>
//
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1435,40 +1547,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1477,28 +1555,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1506,33 +1562,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
//#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1548,12 +1599,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1578,6 +1630,83 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1593,24 +1722,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1627,20 +1748,55 @@
//#define CR10_STOCKDISPLAY
//
// MKS OLED 1.3" 128x64 FULL GRAPHICS CONTROLLER
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
//
// Tiny, but very sharp OLED display
// If there is a pixel shift, try the other controller.
//
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1700,7 +1856,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1765,9 +1921,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
//#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -970,64 +1074,29 @@
#define E4_SENSE_RESISTOR 91
#define E4_MICROSTEPS 16
#endif
#endif // TMC26X
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,89 +1244,65 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
#endif
#endif // L6470
/**
* TWI/I2C BUS
@@ -1482,7 +1554,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1566,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1598,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1608,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1648,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

View File

@@ -33,7 +33,8 @@
#include "stepper.h"
#include "temperature.h"
#include "ultralcd.h"
#include "gcode.h"
#include "parser.h"
#include "serial.h"
#include "bitmap_flags.h"
#if ENABLED(MESH_BED_LEVELING)
@@ -47,11 +48,11 @@
#define PRIME_LENGTH 10.0
#define OOZE_AMOUNT 0.3
#define SIZE_OF_INTERSECTION_CIRCLES 5
#define SIZE_OF_CROSSHAIRS 3
#define INTERSECTION_CIRCLE_RADIUS 5
#define CROSSHAIRS_SIZE 3
#if SIZE_OF_CROSSHAIRS >= SIZE_OF_INTERSECTION_CIRCLES
#error "SIZE_OF_CROSSHAIRS must be less than SIZE_OF_INTERSECTION_CIRCLES."
#if CROSSHAIRS_SIZE >= INTERSECTION_CIRCLE_RADIUS
#error "CROSSHAIRS_SIZE must be less than INTERSECTION_CIRCLE_RADIUS."
#endif
#define G26_OK false
@@ -133,15 +134,11 @@
// External references
extern Planner planner;
#if ENABLED(ULTRA_LCD)
extern char lcd_status_message[];
#endif
inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
// Private functions
static uint16_t circle_flags[16], horizontal_mesh_line_flags[16], vertical_mesh_line_flags[16];
float g26_e_axis_feedrate = 0.020,
float g26_e_axis_feedrate = 0.025,
random_deviation = 0.0;
static bool g26_retracted = false; // Track the retracted state of the nozzle so mismatched
@@ -158,7 +155,7 @@
static int8_t g26_prime_flag;
#if ENABLED(NEWPANEL)
#if ENABLED(ULTIPANEL)
/**
* If the LCD is clicked, cancel, wait for release, return true
@@ -167,7 +164,7 @@
if (!is_lcd_clicked()) return false; // Return if the button isn't pressed
lcd_setstatusPGM(PSTR("Mesh Validation Stopped."), 99);
#if ENABLED(ULTIPANEL)
lcd_quick_feedback();
lcd_quick_feedback(true);
#endif
wait_for_release();
return true;
@@ -183,9 +180,9 @@
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
feedrate_mm_s = feed_rate;
prepare_move_to_destination(); // will ultimately call ubl.line_to_destination_cartesian or ubl.prepare_linear_move_to for UBL_SEGMENTED
feedrate_mm_s = save_feedrate; // restore global feed rate
feedrate_mm_s = save_feedrate;
}
void move_to(const float &rx, const float &ry, const float &z, const float &e_delta) {
@@ -201,11 +198,9 @@
destination[X_AXIS] = current_position[X_AXIS];
destination[Y_AXIS] = current_position[Y_AXIS];
destination[Z_AXIS] = z; // We know the last_z==z or we wouldn't be in this block of code.
destination[E_AXIS] = current_position[E_AXIS];
destination[E_CART] = current_position[E_CART];
G26_line_to_destination(feed_value);
stepper.synchronize();
set_destination_from_current();
}
@@ -217,11 +212,9 @@
destination[X_AXIS] = rx;
destination[Y_AXIS] = ry;
destination[E_AXIS] += e_delta;
destination[E_CART] += e_delta;
G26_line_to_destination(feed_value);
stepper.synchronize();
set_destination_from_current();
}
@@ -246,7 +239,7 @@
*/
inline bool prime_nozzle() {
#if ENABLED(NEWPANEL)
#if ENABLED(ULTIPANEL)
float Total_Prime = 0.0;
if (g26_prime_flag == -1) { // The user wants to control how much filament gets purged
@@ -261,27 +254,25 @@
while (!is_lcd_clicked()) {
lcd_chirp();
destination[E_AXIS] += 0.25;
destination[E_CART] += 0.25;
#ifdef PREVENT_LENGTHY_EXTRUDE
Total_Prime += 0.25;
if (Total_Prime >= EXTRUDE_MAXLENGTH) return G26_ERR;
#endif
G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
stepper.synchronize(); // Without this synchronize, the purge is more consistent,
set_destination_from_current();
planner.synchronize(); // Without this synchronize, the purge is more consistent,
// but because the planner has a buffer, we won't be able
// to stop as quickly. So we put up with the less smooth
// action to give the user a more responsive 'Stop'.
set_destination_from_current();
idle();
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
}
wait_for_release();
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_quick_feedback();
lcd_quick_feedback(true);
lcd_external_control = false;
}
else
@@ -289,12 +280,11 @@
{
#if ENABLED(ULTRA_LCD)
lcd_setstatusPGM(PSTR("Fixed Length Prime."), 99);
lcd_quick_feedback();
lcd_quick_feedback(true);
#endif
set_destination_from_current();
destination[E_AXIS] += g26_prime_length;
destination[E_CART] += g26_prime_length;
G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
stepper.synchronize();
set_destination_from_current();
retract_filament(destination);
}
@@ -368,7 +358,7 @@
// 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) < FABS(line_length))
if (dist_end < dist_start && (INTERSECTION_CIRCLE_RADIUS) < ABS(line_length))
return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz);
// Decide whether to retract & bump
@@ -394,7 +384,7 @@
for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) {
for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
#if ENABLED(NEWPANEL)
#if ENABLED(ULTIPANEL)
if (user_canceled()) return true; // Check if the user wants to stop the Mesh Validation
#endif
@@ -408,8 +398,8 @@
// We found two circles that need a horizontal line to connect them
// Print it!
//
sx = _GET_MESH_X( i ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // right edge
ex = _GET_MESH_X(i + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // left edge
sx = _GET_MESH_X( i ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // right edge
ex = _GET_MESH_X(i + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // left edge
sx = constrain(sx, X_MIN_POS + 1, X_MAX_POS - 1);
sy = ey = constrain(_GET_MESH_Y(j), Y_MIN_POS + 1, Y_MAX_POS - 1);
@@ -441,8 +431,8 @@
// We found two circles that need a vertical line to connect them
// Print it!
//
sy = _GET_MESH_Y( j ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // top edge
ey = _GET_MESH_Y(j + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // bottom edge
sy = _GET_MESH_Y( j ) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // top edge
ey = _GET_MESH_Y(j + 1) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)); // bottom edge
sx = ex = constrain(_GET_MESH_X(i), X_MIN_POS + 1, X_MAX_POS - 1);
sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1);
@@ -480,17 +470,19 @@
*/
inline bool turn_on_heaters() {
millis_t next = millis() + 5000UL;
#if HAS_TEMP_BED
#if HAS_HEATED_BED
#if ENABLED(ULTRA_LCD)
if (g26_bed_temp > 25) {
lcd_setstatusPGM(PSTR("G26 Heating Bed."), 99);
lcd_quick_feedback();
lcd_external_control = true;
lcd_quick_feedback(true);
#if ENABLED(ULTIPANEL)
lcd_external_control = true;
#endif
#endif
thermalManager.setTargetBed(g26_bed_temp);
while (abs(thermalManager.degBed() - g26_bed_temp) > 3) {
while (ABS(thermalManager.degBed() - g26_bed_temp) > 3) {
#if ENABLED(NEWPANEL)
#if ENABLED(ULTIPANEL)
if (is_lcd_clicked()) return exit_from_g26();
#endif
@@ -500,19 +492,20 @@
SERIAL_EOL();
}
idle();
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
}
#if ENABLED(ULTRA_LCD)
}
lcd_setstatusPGM(PSTR("G26 Heating Nozzle."), 99);
lcd_quick_feedback();
lcd_quick_feedback(true);
#endif
#endif
// Start heating the nozzle and wait for it to reach temperature.
thermalManager.setTargetHotend(g26_hotend_temp, 0);
while (abs(thermalManager.degHotend(0) - g26_hotend_temp) > 3) {
while (ABS(thermalManager.degHotend(0) - g26_hotend_temp) > 3) {
#if ENABLED(NEWPANEL)
#if ENABLED(ULTIPANEL)
if (is_lcd_clicked()) return exit_from_g26();
#endif
@@ -522,11 +515,12 @@
SERIAL_EOL();
}
idle();
}
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
}
#if ENABLED(ULTRA_LCD)
lcd_reset_status();
lcd_quick_feedback();
lcd_quick_feedback(true);
#endif
return G26_OK;
@@ -543,12 +537,27 @@
*
* Used to interactively edit the mesh by placing the
* nozzle in a problem area and doing a G29 P4 R command.
*
* Parameters:
*
* B Bed Temperature
* C Continue from the Closest mesh point
* D Disable leveling before starting
* F Filament diameter
* H Hotend Temperature
* K Keep heaters on when completed
* L Layer Height
* O Ooze extrusion length
* P Prime length
* Q Retraction multiplier
* R Repetitions (number of grid points)
* S Nozzle Size (diameter) in mm
* U Random deviation (50 if no value given)
* X X position
* Y Y position
*/
void gcode_G26() {
SERIAL_ECHOLNPGM("G26 command started. Waiting for heater(s).");
float tmp, start_angle, end_angle;
int i, xi, yi;
mesh_index_pair location;
// Don't allow Mesh Validation without homing first,
// or if the parameter parsing did not go OK, abort
@@ -571,8 +580,8 @@
if (parser.seenval('B')) {
g26_bed_temp = parser.value_celsius();
if (!WITHIN(g26_bed_temp, 15, 140)) {
SERIAL_PROTOCOLLNPGM("?Specified bed temperature not plausible.");
if (g26_bed_temp && !WITHIN(g26_bed_temp, 40, 140)) {
SERIAL_PROTOCOLLNPGM("?Specified bed temperature not plausible (40-140C).");
return;
}
}
@@ -609,7 +618,7 @@
if (parser.seen('P')) {
if (!parser.has_value()) {
#if ENABLED(NEWPANEL)
#if ENABLED(ULTIPANEL)
g26_prime_flag = -1;
#else
SERIAL_PROTOCOLLNPGM("?Prime length must be specified when not using an LCD.");
@@ -654,7 +663,7 @@
}
int16_t g26_repeats;
#if ENABLED(NEWPANEL)
#if ENABLED(ULTIPANEL)
g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1);
#else
if (!parser.seen('R')) {
@@ -683,13 +692,12 @@
if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) {
do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
stepper.synchronize();
set_current_from_destination();
}
if (turn_on_heaters() != G26_OK) goto LEAVE;
current_position[E_AXIS] = 0.0;
current_position[E_CART] = 0.0;
sync_plan_position_e();
if (g26_prime_flag && prime_nozzle() != G26_OK) goto LEAVE;
@@ -714,24 +722,35 @@
move_to(destination, 0.0);
move_to(destination, g26_ooze_amount);
#if ENABLED(ULTRA_LCD)
#if ENABLED(ULTIPANEL)
lcd_external_control = true;
#endif
//debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern."));
/**
* Declare and generate a sin() & cos() table to be used during the circle drawing. This will lighten
* the CPU load and make the arc drawing faster and more smooth
*/
float sin_table[360 / 30 + 1], cos_table[360 / 30 + 1];
for (i = 0; i <= 360 / 30; i++) {
cos_table[i] = SIZE_OF_INTERSECTION_CIRCLES * cos(RADIANS(valid_trig_angle(i * 30.0)));
sin_table[i] = SIZE_OF_INTERSECTION_CIRCLES * sin(RADIANS(valid_trig_angle(i * 30.0)));
}
#if DISABLED(ARC_SUPPORT)
/**
* Pre-generate radius offset values at 30 degree intervals to reduce CPU load.
*/
#define A_INT 30
#define _ANGS (360 / A_INT)
#define A_CNT (_ANGS / 2)
#define _IND(A) ((A + _ANGS * 8) % _ANGS)
#define _COS(A) (trig_table[_IND(A) % A_CNT] * (_IND(A) >= A_CNT ? -1 : 1))
#define _SIN(A) (-_COS((A + A_CNT / 2) % _ANGS))
#if A_CNT & 1
#error "A_CNT must be a positive value. Please change A_INT."
#endif
float trig_table[A_CNT];
for (uint8_t i = 0; i < A_CNT; i++)
trig_table[i] = INTERSECTION_CIRCLE_RADIUS * cos(RADIANS(i * A_INT));
#endif // !ARC_SUPPORT
mesh_index_pair location;
do {
location = g26_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(g26_x_pos, g26_y_pos); // Find the closest Mesh Intersection to where we are now.
@@ -740,87 +759,133 @@
circle_y = _GET_MESH_Y(location.y_index);
// If this mesh location is outside the printable_radius, skip it.
if (!position_is_reachable(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;
// Determine where to start and end the circle,
// which is always drawn counter-clockwise.
const uint8_t xi = location.x_index, yi = location.y_index;
const bool f = yi == 0, r = xi >= GRID_MAX_POINTS_X - 1, b = yi >= GRID_MAX_POINTS_Y - 1;
if (g26_debug_flag) {
SERIAL_ECHOPAIR(" Doing circle at: (xi=", xi);
SERIAL_ECHOPAIR(", yi=", yi);
SERIAL_CHAR(')');
SERIAL_EOL();
}
#if ENABLED(ARC_SUPPORT)
start_angle = 0.0; // assume it is going to be a full circle
end_angle = 360.0;
if (xi == 0) { // Check for bottom edge
start_angle = -90.0;
end_angle = 90.0;
if (yi == 0) // it is an edge, check for the two left corners
start_angle = 0.0;
else if (yi == GRID_MAX_POINTS_Y - 1)
end_angle = 0.0;
}
else if (xi == GRID_MAX_POINTS_X - 1) { // Check for top edge
start_angle = 90.0;
end_angle = 270.0;
if (yi == 0) // it is an edge, check for the two right corners
end_angle = 180.0;
else if (yi == GRID_MAX_POINTS_Y - 1)
start_angle = 180.0;
}
else if (yi == 0) {
start_angle = 0.0; // only do the top side of the cirlce
end_angle = 180.0;
}
else if (yi == GRID_MAX_POINTS_Y - 1) {
start_angle = 180.0; // only do the bottom side of the cirlce
end_angle = 360.0;
}
#define ARC_LENGTH(quarters) (INTERSECTION_CIRCLE_RADIUS * M_PI * (quarters) / 2)
float sx = circle_x + INTERSECTION_CIRCLE_RADIUS, // default to full circle
ex = circle_x + INTERSECTION_CIRCLE_RADIUS,
sy = circle_y, ey = circle_y,
arc_length = ARC_LENGTH(4);
for (tmp = start_angle; tmp < end_angle - 0.1; tmp += 30.0) {
// Figure out where to start and end the arc - we always print counterclockwise
if (xi == 0) { // left edge
sx = f ? circle_x + INTERSECTION_CIRCLE_RADIUS : circle_x;
ex = b ? circle_x + INTERSECTION_CIRCLE_RADIUS : circle_x;
sy = f ? circle_y : circle_y - INTERSECTION_CIRCLE_RADIUS;
ey = b ? circle_y : circle_y + INTERSECTION_CIRCLE_RADIUS;
arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
}
else if (r) { // right edge
sx = b ? circle_x - INTERSECTION_CIRCLE_RADIUS : circle_x;
ex = f ? circle_x - INTERSECTION_CIRCLE_RADIUS : circle_x;
sy = b ? circle_y : circle_y + INTERSECTION_CIRCLE_RADIUS;
ey = f ? circle_y : circle_y - INTERSECTION_CIRCLE_RADIUS;
arc_length = (f || b) ? ARC_LENGTH(1) : ARC_LENGTH(2);
}
else if (f) {
sx = circle_x + INTERSECTION_CIRCLE_RADIUS;
ex = circle_x - INTERSECTION_CIRCLE_RADIUS;
sy = ey = circle_y;
arc_length = ARC_LENGTH(2);
}
else if (b) {
sx = circle_x - INTERSECTION_CIRCLE_RADIUS;
ex = circle_x + INTERSECTION_CIRCLE_RADIUS;
sy = ey = circle_y;
arc_length = ARC_LENGTH(2);
}
const float arc_offset[2] = {
circle_x - sx,
circle_y - sy
};
#if ENABLED(NEWPANEL)
if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation
const float dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual circle
dy_s = current_position[Y_AXIS] - sy,
dist_start = HYPOT2(dx_s, dy_s);
const float endpoint[XYZE] = {
ex, ey,
g26_layer_height,
current_position[E_CART] + (arc_length * g26_e_axis_feedrate * g26_extrusion_multiplier)
};
if (dist_start > 2.0) {
retract_filament(destination);
//todo: parameterize the bump height with a define
move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + 0.500, 0.0); // Z bump to minimize scraping
move_to(sx, sy, g26_layer_height + 0.500, 0.0); // Get to the starting point with no extrusion while bumped
}
move_to(sx, sy, g26_layer_height, 0.0); // Get to the starting point with no extrusion / un-Z bump
recover_filament(destination);
const float save_feedrate = feedrate_mm_s;
feedrate_mm_s = PLANNER_XY_FEEDRATE() / 10.0;
plan_arc(endpoint, arc_offset, false); // Draw a counter-clockwise arc
feedrate_mm_s = save_feedrate;
set_destination_from_current();
#if ENABLED(ULTIPANEL)
if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation
#endif
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;
#else // !ARC_SUPPORT
float rx = circle_x + cos_table[tmp_div_30], // for speed, these are now a lookup table entry
ry = 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];
#if IS_KINEMATIC
// Check to make sure this segment is entirely on the bed, skip if not.
if (!position_is_reachable(rx, ry) || !position_is_reachable(xe, ye)) continue;
#else // not, we need to skip
rx = constrain(rx, X_MIN_POS + 1, X_MAX_POS - 1); // This keeps us from bumping the endstops
ry = constrain(ry, Y_MIN_POS + 1, Y_MAX_POS - 1);
xe = constrain(xe, X_MIN_POS + 1, X_MAX_POS - 1);
ye = constrain(ye, Y_MIN_POS + 1, Y_MAX_POS - 1);
#endif
int8_t start_ind = -2, end_ind = 9; // Assume a full circle (from 5:00 to 5:00)
if (xi == 0) { // Left edge? Just right half.
start_ind = f ? 0 : -3; // 03:00 to 12:00 for front-left
end_ind = b ? 0 : 2; // 06:00 to 03:00 for back-left
}
else if (r) { // Right edge? Just left half.
start_ind = b ? 6 : 3; // 12:00 to 09:00 for front-right
end_ind = f ? 5 : 8; // 09:00 to 06:00 for back-right
}
else if (f) { // Front edge? Just back half.
start_ind = 0; // 03:00
end_ind = 5; // 09:00
}
else if (b) { // Back edge? Just front half.
start_ind = 6; // 09:00
end_ind = 11; // 03:00
}
//if (g26_debug_flag) {
// char ccc, *cptr, seg_msg[50], seg_num[10];
// strcpy(seg_msg, " segment: ");
// strcpy(seg_num, " \n");
// cptr = (char*) "01234567890ABCDEF????????";
// ccc = cptr[tmp_div_30];
// seg_num[1] = ccc;
// strcat(seg_msg, seg_num);
// debug_current_and_destination(seg_msg);
//}
for (int8_t ind = start_ind; ind <= end_ind; ind++) {
print_line_from_here_to_there(rx, ry, g26_layer_height, xe, ye, g26_layer_height);
#if ENABLED(ULTIPANEL)
if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation
#endif
}
if (look_for_lines_to_connect())
goto LEAVE;
float rx = circle_x + _COS(ind), // For speed, these are now a lookup table entry
ry = circle_y + _SIN(ind),
xe = circle_x + _COS(ind + 1),
ye = circle_y + _SIN(ind + 1);
#if IS_KINEMATIC
// Check to make sure this segment is entirely on the bed, skip if not.
if (!position_is_reachable(rx, ry) || !position_is_reachable(xe, ye)) continue;
#else // not, we need to skip
rx = constrain(rx, X_MIN_POS + 1, X_MAX_POS - 1); // This keeps us from bumping the endstops
ry = constrain(ry, Y_MIN_POS + 1, Y_MAX_POS - 1);
xe = constrain(xe, X_MIN_POS + 1, X_MAX_POS - 1);
ye = constrain(ye, Y_MIN_POS + 1, Y_MAX_POS - 1);
#endif
print_line_from_here_to_there(rx, ry, g26_layer_height, xe, ye, g26_layer_height);
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
}
#endif // !ARC_SUPPORT
if (look_for_lines_to_connect()) goto LEAVE;
}
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
} while (--g26_repeats && location.x_index >= 0 && location.y_index >= 0);
LEAVE:
@@ -840,12 +905,12 @@
move_to(destination, 0); // Move back to the starting position
//debug_current_and_destination(PSTR("done doing X/Y move."));
#if ENABLED(ULTRA_LCD)
#if ENABLED(ULTIPANEL)
lcd_external_control = false; // Give back control of the LCD Panel!
#endif
if (!g26_keep_heaters_on) {
#if HAS_TEMP_BED
#if HAS_HEATED_BED
thermalManager.setTargetBed(0);
#endif
thermalManager.setTargetHotend(0, 0);

337
Marlin/HAL.h Normal file
View File

@@ -0,0 +1,337 @@
/* **************************************************************************
Marlin 3D Printer Firmware
Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
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 <http://www.gnu.org/licenses/>.
****************************************************************************/
/**
* Description: HAL for __AVR__
*/
#ifndef _HAL_AVR_H_
#define _HAL_AVR_H_
// --------------------------------------------------------------------------
// Includes
// --------------------------------------------------------------------------
#include "fastio.h"
#include <stdint.h>
#include <Arduino.h>
#include <util/delay.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/io.h>
// --------------------------------------------------------------------------
// Defines
// --------------------------------------------------------------------------
//#define analogInputToDigitalPin(IO) IO
// Bracket code that shouldn't be interrupted
#ifndef CRITICAL_SECTION_START
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli()
#define CRITICAL_SECTION_END SREG = _sreg
#endif
#define ISRS_ENABLED() TEST(SREG, SREG_I)
#define ENABLE_ISRS() sei()
#define DISABLE_ISRS() cli()
// --------------------------------------------------------------------------
// Types
// --------------------------------------------------------------------------
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
typedef int8_t pin_t;
#define HAL_SERVO_LIB Servo
// --------------------------------------------------------------------------
// Public Variables
// --------------------------------------------------------------------------
//extern uint8_t MCUSR;
// --------------------------------------------------------------------------
// Public functions
// --------------------------------------------------------------------------
//void cli(void);
//void _delay_ms(const int delay);
inline void HAL_clear_reset_source(void) { MCUSR = 0; }
inline uint8_t HAL_get_reset_source(void) { return MCUSR; }
// eeprom
//void eeprom_write_byte(unsigned char *pos, unsigned char value);
//unsigned char eeprom_read_byte(unsigned char *pos);
// timers
#define HAL_TIMER_RATE ((F_CPU) / 8) // i.e., 2MHz or 2.5MHz
#define STEP_TIMER_NUM 1
#define TEMP_TIMER_NUM 0
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#define TEMP_TIMER_FREQUENCY ((F_CPU) / 64.0 / 256.0)
#define STEPPER_TIMER_RATE HAL_TIMER_RATE
#define STEPPER_TIMER_PRESCALE 8
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // Cannot be of type double
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A)
#define STEPPER_ISR_ENABLED() TEST(TIMSK1, OCIE1A)
#define ENABLE_TEMPERATURE_INTERRUPT() SBI(TIMSK0, OCIE0B)
#define DISABLE_TEMPERATURE_INTERRUPT() CBI(TIMSK0, OCIE0B)
#define TEMPERATURE_ISR_ENABLED() TEST(TIMSK0, OCIE0B)
FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
UNUSED(frequency);
switch (timer_num) {
case STEP_TIMER_NUM:
// waveform generation = 0100 = CTC
SET_WGM(1, CTC_OCRnA);
// output mode = 00 (disconnected)
SET_COMA(1, NORMAL);
// Set the timer pre-scaler
// Generally we use a divider of 8, resulting in a 2MHz timer
// frequency on a 16MHz MCU. If you are going to change this, be
// sure to regenerate speed_lookuptable.h with
// create_speed_lookuptable.py
SET_CS(1, PRESCALER_8); // CS 2 = 1/8 prescaler
// Init Stepper ISR to 122 Hz for quick starting
// (F_CPU) / (STEPPER_TIMER_PRESCALE) / frequency
OCR1A = 0x4000;
TCNT1 = 0;
break;
case TEMP_TIMER_NUM:
// Use timer0 for temperature measurement
// Interleave temperature interrupt with millies interrupt
OCR0B = 128;
break;
}
}
#define TIMER_OCR_1 OCR1A
#define TIMER_COUNTER_1 TCNT1
#define TIMER_OCR_0 OCR0A
#define TIMER_COUNTER_0 TCNT0
#define _CAT(a, ...) a ## __VA_ARGS__
#define HAL_timer_set_compare(timer, compare) (_CAT(TIMER_OCR_, timer) = compare)
#define HAL_timer_get_compare(timer) _CAT(TIMER_OCR_, timer)
#define HAL_timer_get_count(timer) _CAT(TIMER_COUNTER_, timer)
/**
* On AVR there is no hardware prioritization and preemption of
* interrupts, so this emulates it. The UART has first priority
* (otherwise, characters will be lost due to UART overflow).
* Then: Stepper, Endstops, Temperature, and -finally- all others.
*/
#define HAL_timer_isr_prologue(TIMER_NUM)
#define HAL_timer_isr_epilogue(TIMER_NUM)
/* 18 cycles maximum latency */
#define HAL_STEP_TIMER_ISR \
extern "C" void TIMER1_COMPA_vect (void) __attribute__ ((signal, naked, used, externally_visible)); \
extern "C" void TIMER1_COMPA_vect_bottom (void) asm ("TIMER1_COMPA_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
void TIMER1_COMPA_vect (void) { \
__asm__ __volatile__ ( \
A("push r16") /* 2 Save R16 */ \
A("in r16, __SREG__") /* 1 Get SREG */ \
A("push r16") /* 2 Save SREG into stack */ \
A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \
A("push r16") /* 2 Save TIMSK0 into the stack */ \
A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \
A("sts %[timsk0], r16") /* 2 And set the new value */ \
A("lds r16, %[timsk1]") /* 2 Load into R0 the stepper timer Interrupt mask register [TIMSK1] */ \
A("andi r16,~%[msk1]") /* 1 Disable the stepper ISR */ \
A("sts %[timsk1], r16") /* 2 And set the new value */ \
A("push r16") /* 2 Save TIMSK1 into stack */ \
A("in r16, 0x3B") /* 1 Get RAMPZ register */ \
A("push r16") /* 2 Save RAMPZ into stack */ \
A("in r16, 0x3C") /* 1 Get EIND register */ \
A("push r0") /* C runtime can modify all the following registers without restoring them */ \
A("push r1") \
A("push r18") \
A("push r19") \
A("push r20") \
A("push r21") \
A("push r22") \
A("push r23") \
A("push r24") \
A("push r25") \
A("push r26") \
A("push r27") \
A("push r30") \
A("push r31") \
A("clr r1") /* C runtime expects this register to be 0 */ \
A("call TIMER1_COMPA_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \
A("pop r31") \
A("pop r30") \
A("pop r27") \
A("pop r26") \
A("pop r25") \
A("pop r24") \
A("pop r23") \
A("pop r22") \
A("pop r21") \
A("pop r20") \
A("pop r19") \
A("pop r18") \
A("pop r1") \
A("pop r0") \
A("out 0x3C, r16") /* 1 Restore EIND register */ \
A("pop r16") /* 2 Get the original RAMPZ register value */ \
A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \
A("pop r16") /* 2 Get the original TIMSK1 value but with stepper ISR disabled */ \
A("ori r16,%[msk1]") /* 1 Reenable the stepper ISR */ \
A("cli") /* 1 Disable global interrupts - Reenabling Stepper ISR can reenter amd temperature can reenter, and we want that, if it happens, after this ISR has ended */ \
A("sts %[timsk1], r16") /* 2 And restore the old value - This reenables the stepper ISR */ \
A("pop r16") /* 2 Get the temperature timer Interrupt mask register [TIMSK0] */ \
A("sts %[timsk0], r16") /* 2 And restore the old value - This reenables the temperature ISR */ \
A("pop r16") /* 2 Get the old SREG value */ \
A("out __SREG__, r16") /* 1 And restore the SREG value */ \
A("pop r16") /* 2 Restore R16 value */ \
A("reti") /* 4 Return from interrupt */ \
: \
: [timsk0] "i" ((uint16_t)&TIMSK0), \
[timsk1] "i" ((uint16_t)&TIMSK1), \
[msk0] "M" ((uint8_t)(1<<OCIE0B)),\
[msk1] "M" ((uint8_t)(1<<OCIE1A)) \
: \
); \
} \
void TIMER1_COMPA_vect_bottom(void)
/* 14 cycles maximum latency */
#define HAL_TEMP_TIMER_ISR \
extern "C" void TIMER0_COMPB_vect (void) __attribute__ ((signal, naked, used, externally_visible)); \
extern "C" void TIMER0_COMPB_vect_bottom(void) asm ("TIMER0_COMPB_vect_bottom") __attribute__ ((used, externally_visible, noinline)); \
void TIMER0_COMPB_vect (void) { \
__asm__ __volatile__ ( \
A("push r16") /* 2 Save R16 */ \
A("in r16, __SREG__") /* 1 Get SREG */ \
A("push r16") /* 2 Save SREG into stack */ \
A("lds r16, %[timsk0]") /* 2 Load into R0 the Temperature timer Interrupt mask register */ \
A("andi r16,~%[msk0]") /* 1 Disable the temperature ISR */ \
A("sts %[timsk0], r16") /* 2 And set the new value */ \
A("sei") /* 1 Enable global interrupts - It is safe, as the temperature ISR is disabled, so we cannot reenter it */ \
A("push r16") /* 2 Save TIMSK0 into stack */ \
A("in r16, 0x3B") /* 1 Get RAMPZ register */ \
A("push r16") /* 2 Save RAMPZ into stack */ \
A("in r16, 0x3C") /* 1 Get EIND register */ \
A("push r0") /* C runtime can modify all the following registers without restoring them */ \
A("push r1") \
A("push r18") \
A("push r19") \
A("push r20") \
A("push r21") \
A("push r22") \
A("push r23") \
A("push r24") \
A("push r25") \
A("push r26") \
A("push r27") \
A("push r30") \
A("push r31") \
A("clr r1") /* C runtime expects this register to be 0 */ \
A("call TIMER0_COMPB_vect_bottom") /* Call the bottom handler - No inlining allowed, otherwise registers used are not saved */ \
A("pop r31") \
A("pop r30") \
A("pop r27") \
A("pop r26") \
A("pop r25") \
A("pop r24") \
A("pop r23") \
A("pop r22") \
A("pop r21") \
A("pop r20") \
A("pop r19") \
A("pop r18") \
A("pop r1") \
A("pop r0") \
A("out 0x3C, r16") /* 1 Restore EIND register */ \
A("pop r16") /* 2 Get the original RAMPZ register value */ \
A("out 0x3B, r16") /* 1 Restore RAMPZ register to its original value */ \
A("pop r16") /* 2 Get the original TIMSK0 value but with temperature ISR disabled */ \
A("ori r16,%[msk0]") /* 1 Enable temperature ISR */ \
A("cli") /* 1 Disable global interrupts - We must do this, as we will reenable the temperature ISR, and we don't want to reenter this handler until the current one is done */ \
A("sts %[timsk0], r16") /* 2 And restore the old value */ \
A("pop r16") /* 2 Get the old SREG */ \
A("out __SREG__, r16") /* 1 And restore the SREG value */ \
A("pop r16") /* 2 Restore R16 */ \
A("reti") /* 4 Return from interrupt */ \
: \
: [timsk0] "i"((uint16_t)&TIMSK0), \
[msk0] "M" ((uint8_t)(1<<OCIE0B)) \
: \
); \
} \
void TIMER0_COMPB_vect_bottom(void)
// ADC
#ifdef DIDR2
#define HAL_ANALOG_SELECT(pin) do{ if (pin < 8) SBI(DIDR0, pin); else SBI(DIDR2, pin & 0x07); }while(0)
#else
#define HAL_ANALOG_SELECT(pin) do{ SBI(DIDR0, pin); }while(0)
#endif
inline void HAL_adc_init(void) {
ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
DIDR0 = 0;
#ifdef DIDR2
DIDR2 = 0;
#endif
}
#define SET_ADMUX_ADCSRA(pin) ADMUX = _BV(REFS0) | (pin & 0x07); SBI(ADCSRA, ADSC)
#ifdef MUX5
#define HAL_START_ADC(pin) if (pin > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#else
#define HAL_START_ADC(pin) ADCSRB = 0; SET_ADMUX_ADCSRA(pin)
#endif
#define HAL_READ_ADC() ADC
#define HAL_ADC_READY() !TEST(ADCSRA, ADSC)
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
#define HAL_SENSITIVE_PINS 0, 1
#endif // _HAL_AVR_H_

View File

@@ -36,7 +36,7 @@
#include "temperature.h"
#include "stepper.h"
#include "I2CPositionEncoder.h"
#include "gcode.h"
#include "parser.h"
#include <Wire.h>
@@ -99,7 +99,7 @@
//the encoder likely lost its place when the error occured, so we'll reset and use the printer's
//idea of where it the axis is to re-initialise
float position = stepper.get_axis_position_mm(encoderAxis);
float position = planner.get_axis_position_mm(encoderAxis);
int32_t positionInTicks = position * get_ticks_unit();
//shift position from previous to current position
@@ -117,7 +117,7 @@
SERIAL_ECHOPGM("New position reads as ");
SERIAL_ECHO(get_position());
SERIAL_ECHOPGM("(");
SERIAL_CHAR('(');
SERIAL_ECHO(mm_from_count(get_position()));
SERIAL_ECHOLNPGM(")");
#endif
@@ -134,7 +134,7 @@
#ifdef I2CPE_EC_THRESH_PROPORTIONAL
const millis_t deltaTime = positionTime - lastPositionTime;
const uint32_t distance = abs(position - lastPosition),
const uint32_t distance = ABS(position - lastPosition),
speed = distance / deltaTime;
const float threshold = constrain((speed / 50), 1, 50) * ecThreshold;
#else
@@ -150,7 +150,7 @@
LOOP_L_N(i, I2CPE_ERR_ARRAY_SIZE) {
sum += err[i];
if (i) diffSum += abs(err[i-1] - err[i]);
if (i) diffSum += ABS(err[i-1] - err[i]);
}
const int32_t error = int32_t(sum / (I2CPE_ERR_ARRAY_SIZE + 1)); //calculate average for error
@@ -163,7 +163,7 @@
//SERIAL_ECHOLN(error);
#ifdef I2CPE_ERR_THRESH_ABORT
if (labs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) {
if (ABS(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) {
//kill("Significant Error");
SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!");
SERIAL_ECHOLN(error);
@@ -173,26 +173,34 @@
#if ENABLED(I2CPE_ERR_ROLLING_AVERAGE)
if (errIdx == 0) {
// in order to correct for "error" but avoid correcting for noise and non skips
// In order to correct for "error" but avoid correcting for noise and non-skips
// it must be > threshold and have a difference average of < 10 and be < 2000 steps
if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis] &&
diffSum < 10 * (I2CPE_ERR_ARRAY_SIZE - 1) && labs(error) < 2000) { //Check for persistent error (skip)
SERIAL_ECHO(axis_codes[encoderAxis]);
SERIAL_ECHOPAIR(" diffSum: ", diffSum / (I2CPE_ERR_ARRAY_SIZE - 1));
SERIAL_ECHOPAIR(" - err detected: ", error / planner.axis_steps_per_mm[encoderAxis]);
SERIAL_ECHOLNPGM("mm; correcting!");
thermalManager.babystepsTodo[encoderAxis] = -LROUND(error);
if (ABS(error) > threshold * planner.axis_steps_per_mm[encoderAxis] &&
diffSum < 10 * (I2CPE_ERR_ARRAY_SIZE - 1) && ABS(error) < 2000) { // Check for persistent error (skip)
errPrst[errPrstIdx++] = error; // Error must persist for I2CPE_ERR_PRST_ARRAY_SIZE error cycles. This also serves to improve the average accuracy
if (errPrstIdx >= I2CPE_ERR_PRST_ARRAY_SIZE) {
float sumP = 0;
LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i];
const int32_t errorP = int32_t(sumP * (1.0f / (I2CPE_ERR_PRST_ARRAY_SIZE)));
SERIAL_ECHO(axis_codes[encoderAxis]);
SERIAL_ECHOPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis]);
SERIAL_ECHOLNPGM("mm; correcting!");
thermalManager.babystepsTodo[encoderAxis] = -LROUND(errorP);
errPrstIdx = 0;
}
}
else
errPrstIdx = 0;
}
#else
if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) {
if (ABS(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) {
//SERIAL_ECHOLN(error);
//SERIAL_ECHOLN(position);
thermalManager.babystepsTodo[encoderAxis] = -LROUND(error/2);
thermalManager.babystepsTodo[encoderAxis] = -LROUND(error / 2);
}
#endif
if (labs(error) > I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) {
if (ABS(error) > I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) {
const millis_t ms = millis();
if (ELAPSED(ms, nextErrorCountTime)) {
SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]);
@@ -246,11 +254,11 @@
float I2CPositionEncoder::get_axis_error_mm(const bool report) {
float target, actual, error;
target = stepper.get_axis_position_mm(encoderAxis);
target = planner.get_axis_position_mm(encoderAxis);
actual = mm_from_count(position);
error = actual - target;
if (labs(error) > 10000) error = 0; // ?
if (ABS(error) > 10000) error = 0; // ?
if (report) {
SERIAL_ECHO(axis_codes[encoderAxis]);
@@ -285,7 +293,7 @@
error = (encoderCountInStepperTicksScaled - target);
//suppress discontinuities (might be caused by bad I2C readings...?)
bool suppressOutput = (labs(error - errorPrev) > 100);
const bool suppressOutput = (ABS(error - errorPrev) > 100);
if (report) {
SERIAL_ECHO(axis_codes[encoderAxis]);
@@ -341,18 +349,18 @@
ec = false;
LOOP_NA(i) {
startCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
endCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
startCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
endCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
}
startCoord[encoderAxis] = startPosition;
endCoord[encoderAxis] = endPosition;
stepper.synchronize();
planner.synchronize();
planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS],
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
// if the module isn't currently trusted, wait until it is (or until it should be if things are working)
if (!trusted) {
@@ -363,8 +371,8 @@
if (trusted) { // if trusted, commence test
planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
}
return trusted;
@@ -400,34 +408,34 @@
travelDistance = endDistance - startDistance;
LOOP_NA(i) {
startCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
endCoord[i] = stepper.get_axis_position_mm((AxisEnum)i);
startCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
endCoord[i] = planner.get_axis_position_mm((AxisEnum)i);
}
startCoord[encoderAxis] = startDistance;
endCoord[encoderAxis] = endDistance;
LOOP_L_N(i, iter) {
stepper.synchronize();
planner.synchronize();
planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
LOOP_L_N(i, iter) {
planner.buffer_line(startCoord[X_AXIS], startCoord[Y_AXIS], startCoord[Z_AXIS],
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
delay(250);
startCount = get_position();
//do_blocking_move_to(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS]);
planner.buffer_line(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS],
stepper.get_axis_position_mm(E_AXIS), feedrate, 0);
stepper.synchronize();
planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS],
planner.get_axis_position_mm(E_AXIS), feedrate, 0);
planner.synchronize();
//Read encoder distance
delay(250);
stopCount = get_position();
travelledDistance = mm_from_count(abs(stopCount - startCount));
travelledDistance = mm_from_count(ABS(stopCount - startCount));
SERIAL_ECHOPAIR("Attempted to travel: ", travelDistance);
SERIAL_ECHOLNPGM("mm.");

View File

@@ -78,6 +78,7 @@
#if ENABLED(I2CPE_ERR_ROLLING_AVERAGE)
#define I2CPE_ERR_ARRAY_SIZE 32
#define I2CPE_ERR_PRST_ARRAY_SIZE 10
#endif
// Error Correction Methods
@@ -97,8 +98,6 @@
#define LOOP_PE(VAR) LOOP_L_N(VAR, I2CPE_ENCODER_CNT)
#define CHECK_IDX() do{ if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; }while(0)
extern const char axis_codes[XYZE];
typedef union {
volatile int32_t val = 0;
uint8_t bval[4];
@@ -135,15 +134,12 @@
nextErrorCountTime = 0,
lastErrorTime;
//double positionMm; //calculate
#if ENABLED(I2CPE_ERR_ROLLING_AVERAGE)
uint8_t errIdx = 0;
int err[I2CPE_ERR_ARRAY_SIZE] = { 0 };
uint8_t errIdx = 0, errPrstIdx = 0;
int err[I2CPE_ERR_ARRAY_SIZE] = { 0 },
errPrst[I2CPE_ERR_PRST_ARRAY_SIZE] = { 0 };
#endif
//float positionMm; //calculate
public:
void init(const uint8_t address, const AxisEnum axis);
void reset();

View File

@@ -45,25 +45,24 @@
*
* Initial version by Roxy-3D
*/
#define M100_FREE_MEMORY_DUMPER // Enable for the `M110 D` Dump sub-command
#define M100_FREE_MEMORY_CORRUPTOR // Enable for the `M100 C` Corrupt sub-command
#include "MarlinConfig.h"
#if ENABLED(M100_FREE_MEMORY_WATCHER)
#define TEST_BYTE ((char) 0xE5)
#define M100_FREE_MEMORY_DUMPER // Enable for the `M100 D` Dump sub-command
#define M100_FREE_MEMORY_CORRUPTOR // Enable for the `M100 C` Corrupt sub-command
extern char command_queue[BUFSIZE][MAX_CMD_SIZE];
#include "Marlin.h"
#include "parser.h"
#include "hex_print_routines.h"
#define TEST_BYTE ((char) 0xE5)
extern char* __brkval;
extern size_t __heap_start, __heap_end, __flp;
extern char __bss_end;
#include "Marlin.h"
#include "gcode.h"
#include "hex_print_routines.h"
//
// Utility functions
//

View File

@@ -1,4 +1,4 @@
# Sprinter Arduino Project Makefile
# Marlin Firmware Arduino Project Makefile
#
# Makefile Based on:
# Arduino 0011 Makefile
@@ -96,152 +96,296 @@ RELOC_WORKAROUND ?= 1
# HARDWARE_VARIANT = "arduino", "Sanguino", "Gen7", ...
# MCU = "atmega1280", "Mega2560", "atmega2560", "atmega644p", ...
#Gen7
ifeq ($(HARDWARE_MOTHERBOARD),10)
ifeq ($(HARDWARE_MOTHERBOARD),0)
# No motherboard selected
#
# RAMPS 1.3 / 1.4 - ATmega1280, ATmega2560
#
# MEGA/RAMPS up to 1.2
else ifeq ($(HARDWARE_MOTHERBOARD),3)
# RAMPS 1.3 (Power outputs: Hotend, Fan, Bed)
else ifeq ($(HARDWARE_MOTHERBOARD),33)
# RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Bed)
else ifeq ($(HARDWARE_MOTHERBOARD),34)
# RAMPS 1.3 (Power outputs: Hotend, Fan0, Fan1)
else ifeq ($(HARDWARE_MOTHERBOARD),35)
# RAMPS 1.3 (Power outputs: Hotend0, Hotend1, Fan)
else ifeq ($(HARDWARE_MOTHERBOARD),36)
# RAMPS 1.3 (Power outputs: Spindle, Controller Fan)
else ifeq ($(HARDWARE_MOTHERBOARD),38)
# RAMPS 1.4 (Power outputs: Hotend, Fan, Bed)
else ifeq ($(HARDWARE_MOTHERBOARD),43)
# RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Bed)
else ifeq ($(HARDWARE_MOTHERBOARD),44)
# RAMPS 1.4 (Power outputs: Hotend, Fan0, Fan1)
else ifeq ($(HARDWARE_MOTHERBOARD),45)
# RAMPS 1.4 (Power outputs: Hotend0, Hotend1, Fan)
else ifeq ($(HARDWARE_MOTHERBOARD),46)
# RAMPS 1.4 (Power outputs: Spindle, Controller Fan)
else ifeq ($(HARDWARE_MOTHERBOARD),48)
# RAMPS Plus 3DYMY (Power outputs: Hotend, Fan, Bed)
else ifeq ($(HARDWARE_MOTHERBOARD),143)
# RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Bed)
else ifeq ($(HARDWARE_MOTHERBOARD),144)
# RAMPS Plus 3DYMY (Power outputs: Hotend, Fan0, Fan1)
else ifeq ($(HARDWARE_MOTHERBOARD),145)
# RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Fan)
else ifeq ($(HARDWARE_MOTHERBOARD),146)
# RAMPS Plus 3DYMY (Power outputs: Spindle, Controller Fan)
else ifeq ($(HARDWARE_MOTHERBOARD),148)
#
# RAMPS Derivatives - ATmega1280, ATmega2560
#
# 3Drag Controller
else ifeq ($(HARDWARE_MOTHERBOARD),77)
# Velleman K8200 Controller (derived from 3Drag Controller)
else ifeq ($(HARDWARE_MOTHERBOARD),78)
# Velleman K8400 Controller (derived from 3Drag Controller)
else ifeq ($(HARDWARE_MOTHERBOARD),79)
# 2PrintBeta BAM&DICE with STK drivers
else ifeq ($(HARDWARE_MOTHERBOARD),401)
# 2PrintBeta BAM&DICE Due with STK drivers
else ifeq ($(HARDWARE_MOTHERBOARD),402)
# MKS BASE v1.0
else ifeq ($(HARDWARE_MOTHERBOARD),40)
# MKS v1.5 with Allegro A4982 stepper drivers
else ifeq ($(HARDWARE_MOTHERBOARD),405)
# MKS BASE 1.0 with Heroic HR4982 stepper drivers
else ifeq ($(HARDWARE_MOTHERBOARD),41)
# MKS GEN v1.3 or 1.4
else ifeq ($(HARDWARE_MOTHERBOARD),47)
# MKS GEN L
else ifeq ($(HARDWARE_MOTHERBOARD),53)
# zrib V2.0 control board (Chinese knock off RAMPS replica)
else ifeq ($(HARDWARE_MOTHERBOARD),504)
# Felix 2.0+ Electronics Board (RAMPS like)
else ifeq ($(HARDWARE_MOTHERBOARD),37)
# Invent-A-Part RigidBoard
else ifeq ($(HARDWARE_MOTHERBOARD),42)
# Invent-A-Part RigidBoard V2
else ifeq ($(HARDWARE_MOTHERBOARD),52)
# Sainsmart 2-in-1 board
else ifeq ($(HARDWARE_MOTHERBOARD),49)
# Ultimaker
else ifeq ($(HARDWARE_MOTHERBOARD),7)
# Ultimaker (Older electronics. Pre 1.5.4. This is rare)
else ifeq ($(HARDWARE_MOTHERBOARD),71)
MCU ?= atmega1280
# Azteeg X3
else ifeq ($(HARDWARE_MOTHERBOARD),67)
# Azteeg X3 Pro
else ifeq ($(HARDWARE_MOTHERBOARD),68)
# Ultimainboard 2.x (Uses TEMP_SENSOR 20)
else ifeq ($(HARDWARE_MOTHERBOARD),72)
# Rumba
else ifeq ($(HARDWARE_MOTHERBOARD),80)
# bq ZUM Mega 3D
else ifeq ($(HARDWARE_MOTHERBOARD),503)
# MakeBoard Mini v2.1.2 is a control board sold by MicroMake
else ifeq ($(HARDWARE_MOTHERBOARD),431)
# TriGorilla Anycubic version 1.3 based on RAMPS EFB
else ifeq ($(HARDWARE_MOTHERBOARD),343)
# TriGorilla Anycubic version 1.4 based on RAMPS EFB
else ifeq ($(HARDWARE_MOTHERBOARD),443)
# Creality: Ender-4, CR-8
else ifeq ($(HARDWARE_MOTHERBOARD),243)
#
# Other ATmega1280, ATmega2560
#
# Cartesio CN Controls V11
else ifeq ($(HARDWARE_MOTHERBOARD),111)
# Cartesio CN Controls V12
else ifeq ($(HARDWARE_MOTHERBOARD),112)
# Cheaptronic v1.0
else ifeq ($(HARDWARE_MOTHERBOARD),2)
# Cheaptronic v2.0
else ifeq ($(HARDWARE_MOTHERBOARD),21)
# Makerbot Mightyboard Revision E
else ifeq ($(HARDWARE_MOTHERBOARD),200)
# Megatronics
else ifeq ($(HARDWARE_MOTHERBOARD),70)
# Megatronics v2.0
else ifeq ($(HARDWARE_MOTHERBOARD),701)
# Megatronics v3.0
else ifeq ($(HARDWARE_MOTHERBOARD),703)
# Megatronics v3.1
else ifeq ($(HARDWARE_MOTHERBOARD),704)
# Rambo
else ifeq ($(HARDWARE_MOTHERBOARD),301)
# Mini-Rambo
else ifeq ($(HARDWARE_MOTHERBOARD),302)
# Mini-Rambo 1.0a
else ifeq ($(HARDWARE_MOTHERBOARD),303)
# Einsy Rambo
else ifeq ($(HARDWARE_MOTHERBOARD),304)
# Einsy Retro
else ifeq ($(HARDWARE_MOTHERBOARD),305)
# Elefu Ra Board (v3)
else ifeq ($(HARDWARE_MOTHERBOARD),21)
# Leapfrog
else ifeq ($(HARDWARE_MOTHERBOARD),999)
# Mega controller
else ifeq ($(HARDWARE_MOTHERBOARD),310)
# abee Scoovo X9H
else ifeq ($(HARDWARE_MOTHERBOARD),321)
# Geeetech GT2560 Rev. A
else ifeq ($(HARDWARE_MOTHERBOARD),74)
# Geeetech GT2560 Rev. A+ (with auto level probe)
else ifeq ($(HARDWARE_MOTHERBOARD),75)
#
# ATmega1281, ATmega2561
#
else ifeq ($(HARDWARE_MOTHERBOARD),702)
MCU ?= atmega1281
else ifeq ($(HARDWARE_MOTHERBOARD),25)
MCU ?= atmega1281
#
# Sanguinololu and Derivatives - ATmega644P, ATmega1284P
#
# Sanguinololu < 1.2
else ifeq ($(HARDWARE_MOTHERBOARD),6)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
# Sanguinololu 1.2 and above
else ifeq ($(HARDWARE_MOTHERBOARD),62)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
# Melzi
else ifeq ($(HARDWARE_MOTHERBOARD),63)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
# Melzi with ATmega1284 (MaKr3d version)
else ifeq ($(HARDWARE_MOTHERBOARD),66)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
# Melzi Creality3D board (for CR-10 etc)
else ifeq ($(HARDWARE_MOTHERBOARD),89)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
# Melzi Malyan M150 board
else ifeq ($(HARDWARE_MOTHERBOARD),92)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
# Tronxy X5S
else ifeq ($(HARDWARE_MOTHERBOARD),505)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
# STB V1.1
else ifeq ($(HARDWARE_MOTHERBOARD),64)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
# Azteeg X1
else ifeq ($(HARDWARE_MOTHERBOARD),65)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
# Anet 1.0 (Melzi clone)
else ifeq ($(HARDWARE_MOTHERBOARD),69)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
#
# Other ATmega644P, ATmega644, ATmega1284P
#
# Gen3 Monolithic Electronics
else ifeq ($(HARDWARE_MOTHERBOARD),22)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
# Gen3+
else ifeq ($(HARDWARE_MOTHERBOARD),9)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
# Gen6
else ifeq ($(HARDWARE_MOTHERBOARD),5)
HARDWARE_VARIANT ?= Gen6
MCU ?= atmega644p
# Gen6 deluxe
else ifeq ($(HARDWARE_MOTHERBOARD),51)
HARDWARE_VARIANT ?= Gen6
MCU ?= atmega644p
# Gen7 custom (Alfons3 Version)
else ifeq ($(HARDWARE_MOTHERBOARD),10)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega644
F_CPU ?= 20000000
else ifeq ($(HARDWARE_MOTHERBOARD),11)
# Gen7 v1.1, v1.2
else ifeq ($(HARDWARE_MOTHERBOARD),11)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega644p
F_CPU ?= 20000000
else ifeq ($(HARDWARE_MOTHERBOARD),12)
# Gen7 v1.3
else ifeq ($(HARDWARE_MOTHERBOARD),12)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega644p
F_CPU ?= 20000000
else ifeq ($(HARDWARE_MOTHERBOARD),13)
# Gen7 v1.4
else ifeq ($(HARDWARE_MOTHERBOARD),13)
HARDWARE_VARIANT ?= Gen7
MCU ?= atmega1284p
F_CPU ?= 20000000
#RAMPS
else ifeq ($(HARDWARE_MOTHERBOARD),3)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),33)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),34)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),35)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),36)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),38)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),43)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),44)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),45)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),46)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),48)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
#Gen6
else ifeq ($(HARDWARE_MOTHERBOARD),5)
HARDWARE_VARIANT ?= Gen6
MCU ?= atmega644p
else ifeq ($(HARDWARE_MOTHERBOARD),51)
HARDWARE_VARIANT ?= Gen6
MCU ?= atmega644p
#Sanguinololu
else ifeq ($(HARDWARE_MOTHERBOARD),6)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
else ifeq ($(HARDWARE_MOTHERBOARD),62)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
else ifeq ($(HARDWARE_MOTHERBOARD),63)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
else ifeq ($(HARDWARE_MOTHERBOARD),65)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
else ifeq ($(HARDWARE_MOTHERBOARD),66)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
else ifeq ($(HARDWARE_MOTHERBOARD),69)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega1284p
#Ultimaker
else ifeq ($(HARDWARE_MOTHERBOARD),7)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),71)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega1280
#Teensylu
else ifeq ($(HARDWARE_MOTHERBOARD),8)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
else ifeq ($(HARDWARE_MOTHERBOARD),81)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
else ifeq ($(HARDWARE_MOTHERBOARD),811)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
else ifeq ($(HARDWARE_MOTHERBOARD),82)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb646
else ifeq ($(HARDWARE_MOTHERBOARD),83)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
else ifeq ($(HARDWARE_MOTHERBOARD),84)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
#Gen3+
else ifeq ($(HARDWARE_MOTHERBOARD),9)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
#Gen3 Monolithic Electronics
else ifeq ($(HARDWARE_MOTHERBOARD),22)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
#Megatronics
else ifeq ($(HARDWARE_MOTHERBOARD),70)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
#Alpha OMCA board
else ifeq ($(HARDWARE_MOTHERBOARD),90)
# Alpha OMCA board
else ifeq ($(HARDWARE_MOTHERBOARD),90)
HARDWARE_VARIANT ?= SanguinoA
MCU ?= atmega644
#Final OMCA board
else ifeq ($(HARDWARE_MOTHERBOARD),91)
# Final OMCA board
else ifeq ($(HARDWARE_MOTHERBOARD),91)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
# Sethi 3D_1
else ifeq ($(HARDWARE_MOTHERBOARD),20)
HARDWARE_VARIANT ?= Sanguino
MCU ?= atmega644p
#Rambo
else ifeq ($(HARDWARE_MOTHERBOARD),301)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
#
# Teensyduino - AT90USB1286, AT90USB1286P
#
# Azteeg
else ifeq ($(HARDWARE_MOTHERBOARD),67)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
else ifeq ($(HARDWARE_MOTHERBOARD),68)
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
# Teensylu
else ifeq ($(HARDWARE_MOTHERBOARD),8)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
# Printrboard (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),81)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
# Printrboard Revision F (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),811)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
# Brainwave (AT90USB646)
else ifeq ($(HARDWARE_MOTHERBOARD),82)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb646
# Brainwave Pro (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),83)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
# SAV Mk-I (AT90USB1286)
else ifeq ($(HARDWARE_MOTHERBOARD),84)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
# Teensy++2.0 (AT90USB1286) - CLI compile: HARDWARE_MOTHERBOARD=84 make
else ifeq ($(HARDWARE_MOTHERBOARD),85)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
# 5DPrint D8 Driver Board
else ifeq ($(HARDWARE_MOTHERBOARD),88)
HARDWARE_VARIANT ?= Teensy
MCU ?= at90usb1286
endif
@@ -250,6 +394,10 @@ endif
# Set to 16Mhz if not yet set.
F_CPU ?= 16000000
# Set to arduino, ATmega2560 if not yet set.
HARDWARE_VARIANT ?= arduino
MCU ?= atmega2560
# Arduino contained the main source code for the Arduino
# Libraries, the "hardware variant" are for boards
# that derives from that, and their source are present in
@@ -382,9 +530,8 @@ CSTANDARD = -std=gnu99
CXXSTANDARD = -std=gnu++11
CDEBUG = -g$(DEBUG)
CWARN = -Wall -Wstrict-prototypes
CTUNING = -funsigned-char -funsigned-bitfields -fpack-struct \
-fshort-enums -w -ffunction-sections -fdata-sections \
-flto \
CTUNING = -w -fsigned-char -funsigned-bitfields -fpack-struct \
-fshort-enums -ffunction-sections -fdata-sections -flto \
-DARDUINO=$(ARDUINO_VERSION)
ifneq ($(HARDWARE_MOTHERBOARD),)
CTUNING += -DMOTHERBOARD=${HARDWARE_MOTHERBOARD}

View File

@@ -29,14 +29,13 @@
#include <inttypes.h>
#include <util/delay.h>
#include <avr/pgmspace.h>
#include <avr/eeprom.h>
#include <avr/interrupt.h>
#include "MarlinConfig.h"
#ifdef DEBUG_GCODE_PARSER
#include "gcode.h"
#include "parser.h"
#endif
#include "enum.h"
@@ -45,19 +44,15 @@
#include "utility.h"
#include "serial.h"
#if ENABLED(PRINTCOUNTER)
#include "printcounter.h"
#else
#include "stopwatch.h"
#endif
void idle(
#if ENABLED(ADVANCED_PAUSE_FEATURE)
bool no_stepper_sleep = false // pass true to keep steppers from disabling on timeout
#endif
);
void manage_inactivity(bool ignore_stepper_queue = false);
void manage_inactivity(const bool ignore_stepper_queue=false);
extern const char axis_codes[XYZE];
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
extern bool extruder_duplication_enabled;
@@ -65,10 +60,10 @@ void manage_inactivity(bool ignore_stepper_queue = false);
#if HAS_X2_ENABLE
#define enable_X() do{ X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); }while(0)
#define disable_X() do{ X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }while(0)
#define disable_X() do{ X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); CBI(axis_known_position, X_AXIS); }while(0)
#elif HAS_X_ENABLE
#define enable_X() X_ENABLE_WRITE( X_ENABLE_ON)
#define disable_X() do{ X_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }while(0)
#define disable_X() do{ X_ENABLE_WRITE(!X_ENABLE_ON); CBI(axis_known_position, X_AXIS); }while(0)
#else
#define enable_X() NOOP
#define disable_X() NOOP
@@ -76,10 +71,10 @@ void manage_inactivity(bool ignore_stepper_queue = false);
#if HAS_Y2_ENABLE
#define enable_Y() do{ Y_ENABLE_WRITE( Y_ENABLE_ON); Y2_ENABLE_WRITE(Y_ENABLE_ON); }while(0)
#define disable_Y() do{ Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }while(0)
#define disable_Y() do{ Y_ENABLE_WRITE(!Y_ENABLE_ON); Y2_ENABLE_WRITE(!Y_ENABLE_ON); CBI(axis_known_position, Y_AXIS); }while(0)
#elif HAS_Y_ENABLE
#define enable_Y() Y_ENABLE_WRITE( Y_ENABLE_ON)
#define disable_Y() do{ Y_ENABLE_WRITE(!Y_ENABLE_ON); axis_known_position[Y_AXIS] = false; }while(0)
#define disable_Y() do{ Y_ENABLE_WRITE(!Y_ENABLE_ON); CBI(axis_known_position, Y_AXIS); }while(0)
#else
#define enable_Y() NOOP
#define disable_Y() NOOP
@@ -87,10 +82,10 @@ void manage_inactivity(bool ignore_stepper_queue = false);
#if HAS_Z2_ENABLE
#define enable_Z() do{ Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); }while(0)
#define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }while(0)
#define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); CBI(axis_known_position, Z_AXIS); }while(0)
#elif HAS_Z_ENABLE
#define enable_Z() Z_ENABLE_WRITE( Z_ENABLE_ON)
#define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }while(0)
#define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); CBI(axis_known_position, Z_AXIS); }while(0)
#else
#define enable_Z() NOOP
#define disable_Z() NOOP
@@ -101,7 +96,10 @@ void manage_inactivity(bool ignore_stepper_queue = false);
/**
* Mixing steppers synchronize their enable (and direction) together
*/
#if MIXING_STEPPERS > 3
#if MIXING_STEPPERS > 4
#define enable_E0() { E0_ENABLE_WRITE( E_ENABLE_ON); E1_ENABLE_WRITE( E_ENABLE_ON); E2_ENABLE_WRITE( E_ENABLE_ON); E3_ENABLE_WRITE( E_ENABLE_ON); E4_ENABLE_WRITE( E_ENABLE_ON); }
#define disable_E0() { E0_ENABLE_WRITE(!E_ENABLE_ON); E1_ENABLE_WRITE(!E_ENABLE_ON); E2_ENABLE_WRITE(!E_ENABLE_ON); E3_ENABLE_WRITE(!E_ENABLE_ON); E4_ENABLE_WRITE(!E_ENABLE_ON); }
#elif MIXING_STEPPERS > 3
#define enable_E0() { E0_ENABLE_WRITE( E_ENABLE_ON); E1_ENABLE_WRITE( E_ENABLE_ON); E2_ENABLE_WRITE( E_ENABLE_ON); E3_ENABLE_WRITE( E_ENABLE_ON); }
#define disable_E0() { E0_ENABLE_WRITE(!E_ENABLE_ON); E1_ENABLE_WRITE(!E_ENABLE_ON); E2_ENABLE_WRITE(!E_ENABLE_ON); E3_ENABLE_WRITE(!E_ENABLE_ON); }
#elif MIXING_STEPPERS > 2
@@ -164,31 +162,69 @@ void manage_inactivity(bool ignore_stepper_queue = false);
#endif // !MIXING_EXTRUDER
#if ENABLED(HANGPRINTER)
#define enable_A() enable_X()
#define enable_B() enable_Y()
#define enable_C() enable_Z()
#define __D_ENABLE(p) E##p##_ENABLE_WRITE(E_ENABLE_ON)
#define _D_ENABLE(p) __D_ENABLE(p)
#define enable_D() _D_ENABLE(EXTRUDERS)
// Don't allow any axes to be disabled
#undef disable_X
#undef disable_Y
#undef disable_Z
#define disable_X() NOOP
#define disable_Y() NOOP
#define disable_Z() NOOP
#if EXTRUDERS >= 1
#undef disable_E1
#define disable_E1() NOOP
#if EXTRUDERS >= 2
#undef disable_E2
#define disable_E2() NOOP
#if EXTRUDERS >= 3
#undef disable_E3
#define disable_E3() NOOP
#if EXTRUDERS >= 4
#undef disable_E4
#define disable_E4() NOOP
#endif // EXTRUDERS >= 4
#endif // EXTRUDERS >= 3
#endif // EXTRUDERS >= 2
#endif // EXTRUDERS >= 1
#endif // HANGPRINTER
#if ENABLED(G38_PROBE_TARGET)
extern bool G38_move, // flag to tell the interrupt handler that a G38 command is being run
G38_endstop_hit; // flag from the interrupt handler to indicate if the endstop went active
#endif
/**
* The axis order in all axis related arrays is X, Y, Z, E
*/
#define _AXIS(AXIS) AXIS ##_AXIS
void enable_all_steppers();
void disable_e_stepper(const uint8_t e);
void disable_e_steppers();
void disable_all_steppers();
void FlushSerialRequestResend();
void sync_plan_position();
void sync_plan_position_e();
#if IS_KINEMATIC
void sync_plan_position_kinematic();
#define SYNC_PLAN_POSITION_KINEMATIC() sync_plan_position_kinematic()
#else
#define SYNC_PLAN_POSITION_KINEMATIC() sync_plan_position()
#endif
void flush_and_request_resend();
void ok_to_send();
void kill(const char*);
void quickstop_stepper();
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
void handle_filament_runout();
#endif
extern uint8_t marlin_debug_flags;
#define DEBUGGING(F) (marlin_debug_flags & (DEBUG_## F))
@@ -196,37 +232,58 @@ extern bool Running;
inline bool IsRunning() { return Running; }
inline bool IsStopped() { return !Running; }
bool enqueue_and_echo_command(const char* cmd, bool say_ok=false); // Add a single command to the end of the buffer. Return false on failure.
void enqueue_and_echo_commands_P(const char * const cmd); // Set one or more commands to be prioritized over the next Serial/SD command.
bool enqueue_and_echo_command(const char* cmd); // Add a single command to the end of the buffer. Return false on failure.
void enqueue_and_echo_commands_P(const char * const cmd); // Set one or more commands to be prioritized over the next Serial/SD command.
void clear_command_queue();
extern millis_t previous_cmd_ms;
inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); }
#if ENABLED(FAST_PWM_FAN)
void setPwmFrequency(uint8_t pin, int val);
#if ENABLED(M100_FREE_MEMORY_WATCHER) || ENABLED(POWER_LOSS_RECOVERY)
extern char command_queue[BUFSIZE][MAX_CMD_SIZE];
#endif
#define HAS_LCD_QUEUE_NOW (ENABLED(MALYAN_LCD) || (ENABLED(ULTIPANEL) && (ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(PID_AUTOTUNE_MENU) || ENABLED(ADVANCED_PAUSE_FEATURE))))
#define HAS_QUEUE_NOW (ENABLED(SDSUPPORT) || HAS_LCD_QUEUE_NOW)
#if HAS_QUEUE_NOW
// Return only when commands are actually enqueued
void enqueue_and_echo_command_now(const char* cmd);
#if HAS_LCD_QUEUE_NOW
void enqueue_and_echo_commands_now_P(const char * const cmd);
#endif
#endif
extern millis_t previous_move_ms;
inline void reset_stepper_timeout() { previous_move_ms = millis(); }
/**
* Feedrate scaling and conversion
*/
extern float feedrate_mm_s;
extern int16_t feedrate_percentage;
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01f)
extern bool axis_relative_modes[XYZE];
extern uint8_t axis_homed, axis_known_position;
constexpr uint8_t xyz_bits = _BV(X_AXIS) | _BV(Y_AXIS) | _BV(Z_AXIS);
FORCE_INLINE bool all_axes_homed() { return (axis_homed & xyz_bits) == xyz_bits; }
FORCE_INLINE bool all_axes_known() { return (axis_known_position & xyz_bits) == xyz_bits; }
extern bool axis_relative_modes[];
extern bool axis_known_position[XYZ];
extern bool axis_homed[XYZ];
extern volatile bool wait_for_heatup;
#if HAS_RESUME_CONTINUE
extern volatile bool wait_for_user;
#endif
#if HAS_AUTO_REPORTING || ENABLED(HOST_KEEPALIVE_FEATURE)
extern bool suspend_auto_report;
#endif
extern float current_position[XYZE], destination[XYZE];
// Workspace offsets
/**
* Workspace offsets
*/
#if HAS_WORKSPACE_OFFSET
#if HAS_HOME_OFFSET
extern float home_offset[XYZ];
@@ -234,36 +291,26 @@ extern float current_position[XYZE], destination[XYZE];
#if HAS_POSITION_SHIFT
extern float position_shift[XYZ];
#endif
#endif
#if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
extern float workspace_offset[XYZ];
#define WORKSPACE_OFFSET(AXIS) workspace_offset[AXIS]
#elif HAS_HOME_OFFSET
#define WORKSPACE_OFFSET(AXIS) home_offset[AXIS]
#elif HAS_POSITION_SHIFT
#define WORKSPACE_OFFSET(AXIS) position_shift[AXIS]
#if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
extern float workspace_offset[XYZ];
#define WORKSPACE_OFFSET(AXIS) workspace_offset[AXIS]
#elif HAS_HOME_OFFSET
#define WORKSPACE_OFFSET(AXIS) home_offset[AXIS]
#elif HAS_POSITION_SHIFT
#define WORKSPACE_OFFSET(AXIS) position_shift[AXIS]
#endif
#define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + WORKSPACE_OFFSET(AXIS))
#define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - WORKSPACE_OFFSET(AXIS))
#else
#define WORKSPACE_OFFSET(AXIS) 0
#define NATIVE_TO_LOGICAL(POS, AXIS) (POS)
#define LOGICAL_TO_NATIVE(POS, AXIS) (POS)
#endif
#define NATIVE_TO_LOGICAL(POS, AXIS) ((POS) + WORKSPACE_OFFSET(AXIS))
#define LOGICAL_TO_NATIVE(POS, AXIS) ((POS) - WORKSPACE_OFFSET(AXIS))
#if HAS_POSITION_SHIFT || DISABLED(DELTA)
#define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
#define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS)
#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS)
#else
#define LOGICAL_X_POSITION(POS) (POS)
#define LOGICAL_Y_POSITION(POS) (POS)
#define RAW_X_POSITION(POS) (POS)
#define RAW_Y_POSITION(POS) (POS)
#endif
#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS)
#define LOGICAL_X_POSITION(POS) NATIVE_TO_LOGICAL(POS, X_AXIS)
#define LOGICAL_Y_POSITION(POS) NATIVE_TO_LOGICAL(POS, Y_AXIS)
#define LOGICAL_Z_POSITION(POS) NATIVE_TO_LOGICAL(POS, Z_AXIS)
#define RAW_X_POSITION(POS) LOGICAL_TO_NATIVE(POS, X_AXIS)
#define RAW_Y_POSITION(POS) LOGICAL_TO_NATIVE(POS, Y_AXIS)
#define RAW_Z_POSITION(POS) LOGICAL_TO_NATIVE(POS, Z_AXIS)
// Hotend Offsets
#if HOTENDS > 1
@@ -285,16 +332,24 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
void update_software_endstops(const AxisEnum axis);
#endif
#define MAX_COORDINATE_SYSTEMS 9
#if ENABLED(CNC_COORDINATE_SYSTEMS)
#define MAX_COORDINATE_SYSTEMS 9
extern float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ];
bool select_coordinate_system(const int8_t _new);
#endif
void tool_change(const uint8_t tmp_extruder, const float fr_mm_s=0.0, bool no_move=false);
void home_all_axes();
void report_current_position();
#if IS_KINEMATIC
extern float delta[ABC];
#if ENABLED(HANGPRINTER)
extern float line_lengths[ABCD];
#else
extern float delta[ABC];
#endif
void inverse_kinematics(const float raw[XYZ]);
#endif
@@ -313,27 +368,65 @@ void report_current_position();
void recalc_delta_settings();
float delta_safe_distance_from_top();
#if ENABLED(DELTA_FAST_SQRT)
float Q_rsqrt(const float number);
#define _SQRT(n) (1.0f / Q_rsqrt(n))
#else
#define _SQRT(n) SQRT(n)
#endif
// Macro to obtain the Z position of an individual tower
#define DELTA_Z(V,T) V[Z_AXIS] + _SQRT( \
#define DELTA_Z(V,T) V[Z_AXIS] + SQRT( \
delta_diagonal_rod_2_tower[T] - HYPOT2( \
delta_tower[T][X_AXIS] - V[X_AXIS], \
delta_tower[T][Y_AXIS] - V[Y_AXIS] \
) \
)
#define DELTA_IK(V) do { \
#define DELTA_IK(V) do { \
delta[A_AXIS] = DELTA_Z(V, A_AXIS); \
delta[B_AXIS] = DELTA_Z(V, B_AXIS); \
delta[C_AXIS] = DELTA_Z(V, C_AXIS); \
}while(0)
#elif ENABLED(HANGPRINTER)
// Don't collect anchor positions in array because there are no A_x, D_x or D_y
extern float anchor_A_y,
anchor_A_z,
anchor_B_x,
anchor_B_y,
anchor_B_z,
anchor_C_x,
anchor_C_y,
anchor_C_z,
anchor_D_z,
delta_segments_per_second,
line_lengths_origin[ABCD];
void recalc_hangprinter_settings();
#define HANGPRINTER_IK(V) do { \
line_lengths[A_AXIS] = SQRT(sq(anchor_A_z - V[Z_AXIS]) \
+ sq(anchor_A_y - V[Y_AXIS]) \
+ sq( V[X_AXIS])); \
line_lengths[B_AXIS] = SQRT(sq(anchor_B_z - V[Z_AXIS]) \
+ sq(anchor_B_y - V[Y_AXIS]) \
+ sq(anchor_B_x - V[X_AXIS])); \
line_lengths[C_AXIS] = SQRT(sq(anchor_C_z - V[Z_AXIS]) \
+ sq(anchor_C_y - V[Y_AXIS]) \
+ sq(anchor_C_x - V[X_AXIS])); \
line_lengths[D_AXIS] = SQRT(sq( V[X_AXIS]) \
+ sq( V[Y_AXIS]) \
+ sq(anchor_D_z - V[Z_AXIS])); \
}while(0)
// Inverse kinematics at origin
#define HANGPRINTER_IK_ORIGIN(LL) do { \
LL[A_AXIS] = SQRT(sq(anchor_A_z) \
+ sq(anchor_A_y)); \
LL[B_AXIS] = SQRT(sq(anchor_B_z) \
+ sq(anchor_B_y) \
+ sq(anchor_B_x)); \
LL[C_AXIS] = SQRT(sq(anchor_C_z) \
+ sq(anchor_C_y) \
+ sq(anchor_C_x)); \
LL[D_AXIS] = anchor_D_z; \
}while(0)
#elif IS_SCARA
void forward_kinematics_SCARA(const float &a, const float &b);
#endif
@@ -362,9 +455,9 @@ void report_current_position();
float bilinear_z_offset(const float raw[XYZ]);
#endif
#if ENABLED(AUTO_BED_LEVELING_UBL)
typedef struct { double A, B, D; } linear_fit;
linear_fit* lsf_linear_fit(double x[], double y[], double z[], const int);
#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(MESH_BED_LEVELING)
typedef float (*element_2d_fn)(const uint8_t, const uint8_t);
void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, const element_2d_fn fn);
#endif
#if HAS_LEVELING
@@ -377,18 +470,19 @@ void report_current_position();
void set_z_fade_height(const float zfh, const bool do_report=true);
#endif
#if ENABLED(X_DUAL_ENDSTOPS)
extern float x_endstop_adj;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
extern float y_endstop_adj;
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
extern float z_endstop_adj;
#endif
#if HAS_BED_PROBE
extern float zprobe_zoffset;
bool set_probe_deployed(const bool deploy);
#ifdef Z_AFTER_PROBING
void move_z_after_probing();
#endif
enum ProbePtRaise : unsigned char {
PROBE_PT_NONE, // No raise or stow after run_z_probe
PROBE_PT_STOW, // Do a complete stow after run_z_probe
PROBE_PT_RAISE, // Raise to "between" clearance after run_z_probe
PROBE_PT_BIG_RAISE // Raise to big clearance after run_z_probe
};
float probe_pt(const float &rx, const float &ry, const ProbePtRaise raise_after=PROBE_PT_NONE, const uint8_t verbose_level=0, const bool probe_relative=true);
#define DEPLOY_PROBE() set_probe_deployed(true)
#define STOW_PROBE() set_probe_deployed(false)
#else
@@ -415,6 +509,10 @@ void report_current_position();
#endif
#endif
#if ENABLED(USE_CONTROLLER_FAN)
extern int controllerFanSpeed;
#endif
#if ENABLED(BARICUDA)
extern uint8_t baricuda_valve_pressure, baricuda_e_to_p_pressure;
#endif
@@ -429,30 +527,16 @@ void report_current_position();
#endif
#if ENABLED(ADVANCED_PAUSE_FEATURE)
extern int8_t did_pause_print;
extern AdvancedPauseMenuResponse advanced_pause_menu_response;
extern float filament_change_unload_length[EXTRUDERS],
filament_change_load_length[EXTRUDERS];
#endif
#if ENABLED(PID_EXTRUSION_SCALING)
extern int lpq_len;
#endif
#if ENABLED(FWRETRACT)
extern bool autoretract_enabled; // M209 S - Autoretract switch
extern float retract_length, // M207 S - G10 Retract length
retract_feedrate_mm_s, // M207 F - G10 Retract feedrate
retract_zlift, // M207 Z - G10 Retract hop size
retract_recover_length, // M208 S - G11 Recover length
retract_recover_feedrate_mm_s, // M208 F - G11 Recover feedrate
swap_retract_length, // M207 W - G10 Swap Retract length
swap_retract_recover_length, // M208 W - G11 Swap Recover length
swap_retract_recover_feedrate_mm_s; // M208 R - G11 Swap Recover feedrate
#endif
// Print job timer
#if ENABLED(PRINTCOUNTER)
extern PrintCounter print_job_timer;
#else
extern Stopwatch print_job_timer;
#if HAS_POWER_SWITCH
extern bool powersupply_on;
#define PSU_PIN_ON() do{ OUT_WRITE(PS_ON_PIN, PS_ON_AWAKE); powersupply_on = true; }while(0)
#define PSU_PIN_OFF() do{ OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP); powersupply_on = false; }while(0)
#endif
// Handling multiple extruders pins
@@ -469,10 +553,14 @@ void prepare_move_to_destination();
/**
* Blocking movement and shorthand functions
*/
void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s=0.0);
void do_blocking_move_to_x(const float &x, const float &fr_mm_s=0.0);
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);
void do_blocking_move_to(const float rx, const float ry, const float rz, const float &fr_mm_s=0);
void do_blocking_move_to_x(const float &rx, const float &fr_mm_s=0);
void do_blocking_move_to_z(const float &rz, const float &fr_mm_s=0);
void do_blocking_move_to_xy(const float &rx, const float &ry, const float &fr_mm_s=0);
#if ENABLED(ARC_SUPPORT)
void plan_arc(const float(&cart)[XYZE], const float(&offset)[2], const bool clockwise);
#endif
#define HAS_AXIS_UNHOMED_ERR ( \
ENABLED(Z_PROBE_ALLEN_KEY) \
@@ -499,44 +587,61 @@ void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s
extern const float L1, L2;
#endif
inline bool position_is_reachable(const float &rx, const float &ry) {
// Return true if the given point is within the printable area
inline bool position_is_reachable(const float &rx, const float &ry, const float inset=0) {
#if ENABLED(DELTA)
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS);
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS - inset);
#elif ENABLED(HANGPRINTER)
// TODO: This is over simplified. Hangprinter's build volume is _not_ cylindrical.
return HYPOT2(rx, ry) <= sq(HANGPRINTER_PRINTABLE_RADIUS - inset);
#elif IS_SCARA
#if MIDDLE_DEAD_ZONE_R > 0
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(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y) <= sq(L1 + L2);
#endif
#else // CARTESIAN
// To be migrated from MakerArm branch in future
const float R2 = HYPOT2(rx - SCARA_OFFSET_X, ry - SCARA_OFFSET_Y);
return (
R2 <= sq(L1 + L2) - inset
#if MIDDLE_DEAD_ZONE_R > 0
&& R2 >= sq(float(MIDDLE_DEAD_ZONE_R))
#endif
);
#endif
}
inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
// 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(rx, ry)
&& position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER));
}
#if HAS_BED_PROBE
// Return true if the both nozzle and the probe can reach the given point.
// Note: This won't work on SCARA since the probe offset rotates with the arm.
inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
return position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER))
&& position_is_reachable(rx, ry, ABS(MIN_PROBE_EDGE));
}
#endif
#else // CARTESIAN
// Return true if the given position is within the machine bounds.
inline bool position_is_reachable(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);
// Add 0.001 margin to deal with float imprecision
return WITHIN(rx, X_MIN_POS - 0.001f, X_MAX_POS + 0.001f)
&& WITHIN(ry, Y_MIN_POS - 0.001f, Y_MAX_POS + 0.001f);
}
inline bool position_is_reachable_by_probe(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);
}
#if HAS_BED_PROBE
/**
* Return whether the given position is within the bed, and whether the nozzle
* can reach the position required to put the probe at the given position.
*
* Example: For a probe offset of -10,+10, then for the probe to reach 0,0 the
* nozzle must be be able to reach +10,-10.
*/
inline bool position_is_reachable_by_probe(const float &rx, const float &ry) {
return position_is_reachable(rx - (X_PROBE_OFFSET_FROM_EXTRUDER), ry - (Y_PROBE_OFFSET_FROM_EXTRUDER))
&& WITHIN(rx, MIN_PROBE_X - 0.001f, MAX_PROBE_X + 0.001f)
&& WITHIN(ry, MIN_PROBE_Y - 0.001f, MAX_PROBE_Y + 0.001f);
}
#endif
#endif // CARTESIAN
#if !HAS_BED_PROBE
FORCE_INLINE bool position_is_reachable_by_probe(const float &rx, const float &ry) { return position_is_reachable(rx, ry); }
#endif
#endif // MARLIN_H

View File

@@ -1,72 +1,53 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/*
================================================================================
/**
* About Marlin
*
* This firmware is a mashup between Sprinter and grbl.
* - https://github.com/kliment/Sprinter
* - https://github.com/simen/grbl/tree
*/
Marlin Firmware
#include "MarlinConfig.h"
(c) 2011-2018 MarlinFirmware
Portions of Marlin are (c) by their respective authors.
All code complies with GPLv2 and/or GPLv3
#if ENABLED(ULTRA_LCD)
#if ENABLED(LCD_I2C_TYPE_PCF8575)
#include <Wire.h>
#include <LiquidCrystal_I2C.h>
#elif ENABLED(LCD_I2C_TYPE_MCP23017) || ENABLED(LCD_I2C_TYPE_MCP23008)
#include <Wire.h>
#include <LiquidTWI2.h>
#elif ENABLED(LCM1602)
#include <Wire.h>
#include <LCD.h>
#include <LiquidCrystal_I2C.h>
#elif ENABLED(DOGLCD)
#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://github.com/olikraus/U8glib_Arduino)
#else
#include <LiquidCrystal.h> // library for character LCD
#endif
#endif
================================================================================
#if HAS_DIGIPOTSS
#include <SPI.h>
#endif
Greetings! Thank you for choosing Marlin as your 3D printer firmware.
#if ENABLED(DIGIPOT_I2C)
#include <Wire.h>
#endif
To configure Marlin you must edit Configuration.h and Configuration_adv.h
located in the root 'Marlin' folder. Check the example_configurations folder to
see if there's a more suitable starting-point for your specific hardware.
#if ENABLED(HAVE_TMCDRIVER)
#include <SPI.h>
#include <TMC26XStepper.h>
#endif
Before diving in, we recommend the following essential links:
#if ENABLED(HAVE_TMC2130)
#include <SPI.h>
#include <TMC2130Stepper.h>
#endif
Marlin Firmware Official Website
#if ENABLED(HAVE_L6470DRIVER)
#include <SPI.h>
#include <L6470.h>
#endif
- http://marlinfw.org/
The official Marlin Firmware website contains the most up-to-date
documentation. Contributions are always welcome!
Configuration
- https://www.youtube.com/watch?v=3gwWVFtdg-4
A good 20-minute overview of Marlin configuration by Tom Sanladerer.
(Applies to Marlin 1.0.x, so Jerk and Acceleration should be halved.)
Also... https://www.google.com/search?tbs=vid%3A1&q=configure+marlin
- http://marlinfw.org/docs/configuration/configuration.html
Marlin's configuration options are explained in more detail here.
Getting Help
- http://forums.reprap.org/list.php?415
The Marlin Discussion Forum is a great place to get help from other Marlin
users who may have experienced similar issues to your own.
- https://github.com/MarlinFirmware/Marlin/issues
With a free GitHub account you can provide us with feedback, bug reports,
and feature requests via the Marlin Issue Queue.
Contributing
- http://marlinfw.org/docs/development/contributing.html
If you'd like to contribute to Marlin, read this first!
- http://marlinfw.org/docs/development/coding_standards.html
Before submitting code get to know the Coding Standards.
*/

View File

@@ -23,20 +23,26 @@
#ifndef MARLIN_CONFIG_H
#define MARLIN_CONFIG_H
#include "fastio.h"
#include "macros.h"
#include "boards.h"
#include "macros.h"
#include "Version.h"
#include "Configuration.h"
#include "Conditionals_LCD.h"
#include "tmc_macros.h"
#include "drivers.h"
#include "Configuration_adv.h"
#include "pins.h"
#ifndef USBCON
#if USE_MARLINSERIAL
#define HardwareSerial_h // trick to disable the standard HWserial
#endif
#include "Arduino.h"
#include "types.h"
#include "HAL.h"
#include "pins.h"
#include "Conditionals_post.h"
#include "SanityCheck.h"
#include "enum.h"
#include "language.h"
#include "utility.h"
#include "serial.h"
#endif // MARLIN_CONFIG_H

View File

@@ -48,7 +48,7 @@ class SPI<MISO_PIN, MOSI_PIN, SCK_PIN> {
}
FORCE_INLINE static uint8_t receive() {
SPDR = 0;
for (;!TEST(SPSR, SPIF););
while (!TEST(SPSR, SPIF)) { /* nada */ }
return SPDR;
}

View File

@@ -28,13 +28,14 @@
* Modified 28 September 2010 by Mark Sproul
* Modified 14 February 2016 by Andreas Hardtung (added tx buffer)
* Modified 01 October 2017 by Eduardo José Tagle (added XON/XOFF)
* Modified 10 June 2018 by Eduardo José Tagle (See #10991)
*/
// Disable HardwareSerial.cpp to support chips without a UART (Attiny, etc.)
#include "MarlinConfig.h"
#if !defined(USBCON) && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))
#if USE_MARLINSERIAL && (defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H))
#include "MarlinSerial.h"
#include "Marlin.h"
@@ -55,16 +56,15 @@
ring_buffer_r rx_buffer = { { 0 }, 0, 0 };
#if TX_BUFFER_SIZE > 0
ring_buffer_t tx_buffer = { { 0 }, 0, 0 };
static bool _written;
#endif
static bool _written;
#endif
#if ENABLED(SERIAL_XON_XOFF)
constexpr uint8_t XON_XOFF_CHAR_SENT = 0x80; // XON / XOFF Character was sent
constexpr uint8_t XON_XOFF_CHAR_MASK = 0x1F; // XON / XOFF character to send
constexpr uint8_t XON_XOFF_CHAR_SENT = 0x80, // XON / XOFF Character was sent
XON_XOFF_CHAR_MASK = 0x1F; // XON / XOFF character to send
// XON / XOFF character definitions
constexpr uint8_t XON_CHAR = 17;
constexpr uint8_t XOFF_CHAR = 19;
constexpr uint8_t XON_CHAR = 17, XOFF_CHAR = 19;
uint8_t xon_xoff_state = XON_XOFF_CHAR_SENT | XON_CHAR;
#endif
@@ -72,209 +72,296 @@
uint8_t rx_dropped_bytes = 0;
#endif
#if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS)
uint8_t rx_buffer_overruns = 0;
#endif
#if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS)
uint8_t rx_framing_errors = 0;
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
ring_buffer_pos_t rx_max_enqueued = 0;
#endif
// A SW memory barrier, to ensure GCC does not overoptimize loops
#define sw_barrier() asm volatile("": : :"memory");
#if ENABLED(EMERGENCY_PARSER)
#include "emergency_parser.h"
#endif
#include "stepper.h"
#include "language.h"
// "Atomically" read the RX head index value without disabling interrupts:
// This MUST be called with RX interrupts enabled, and CAN'T be called
// from the RX ISR itself!
FORCE_INLINE ring_buffer_pos_t atomic_read_rx_head() {
#if RX_BUFFER_SIZE > 256
// Keep reading until 2 consecutive reads return the same value,
// meaning there was no update in-between caused by an interrupt.
// This works because serial RX interrupts happen at a slower rate
// than successive reads of a variable, so 2 consecutive reads with
// the same value means no interrupt updated it.
ring_buffer_pos_t vold, vnew = rx_buffer.head;
sw_barrier();
do {
vold = vnew;
vnew = rx_buffer.head;
sw_barrier();
} while (vold != vnew);
return vnew;
#else
// With an 8bit index, reads are always atomic. No need for special handling
return rx_buffer.head;
#endif
}
// Currently looking for: M108, M112, M410
// If you alter the parser please don't forget to update the capabilities in Conditionals_post.h
#if RX_BUFFER_SIZE > 256
static volatile bool rx_tail_value_not_stable = false;
static volatile uint16_t rx_tail_value_backup = 0;
#endif
FORCE_INLINE void emergency_parser(const unsigned char c) {
// Set RX tail index, taking into account the RX ISR could interrupt
// the write to this variable in the middle - So a backup strategy
// is used to ensure reads of the correct values.
// -Must NOT be called from the RX ISR -
FORCE_INLINE void atomic_set_rx_tail(ring_buffer_pos_t value) {
#if RX_BUFFER_SIZE > 256
// Store the new value in the backup
rx_tail_value_backup = value;
sw_barrier();
// Flag we are about to change the true value
rx_tail_value_not_stable = true;
sw_barrier();
// Store the new value
rx_buffer.tail = value;
sw_barrier();
// Signal the new value is completely stored into the value
rx_tail_value_not_stable = false;
sw_barrier();
#else
rx_buffer.tail = value;
#endif
}
static e_parser_state state = state_RESET;
switch (state) {
case state_RESET:
switch (c) {
case ' ': break;
case 'N': state = state_N; break;
case 'M': state = state_M; break;
default: state = state_IGNORE;
}
break;
case state_N:
switch (c) {
case '0': case '1': case '2':
case '3': case '4': case '5':
case '6': case '7': case '8':
case '9': case '-': case ' ': break;
case 'M': state = state_M; break;
default: state = state_IGNORE;
}
break;
case state_M:
switch (c) {
case ' ': break;
case '1': state = state_M1; break;
case '4': state = state_M4; break;
default: state = state_IGNORE;
}
break;
case state_M1:
switch (c) {
case '0': state = state_M10; break;
case '1': state = state_M11; break;
default: state = state_IGNORE;
}
break;
case state_M10:
state = (c == '8') ? state_M108 : state_IGNORE;
break;
case state_M11:
state = (c == '2') ? state_M112 : state_IGNORE;
break;
case state_M4:
state = (c == '1') ? state_M41 : state_IGNORE;
break;
case state_M41:
state = (c == '0') ? state_M410 : state_IGNORE;
break;
case state_IGNORE:
if (c == '\n') state = state_RESET;
break;
default:
if (c == '\n') {
switch (state) {
case state_M108:
wait_for_user = wait_for_heatup = false;
break;
case state_M112:
kill(PSTR(MSG_KILLED));
break;
case state_M410:
quickstop_stepper();
break;
default:
break;
}
state = state_RESET;
}
}
}
#endif // EMERGENCY_PARSER
// Get the RX tail index, taking into account the read could be
// interrupting in the middle of the update of that index value
// -Called from the RX ISR -
FORCE_INLINE ring_buffer_pos_t atomic_read_rx_tail() {
#if RX_BUFFER_SIZE > 256
// If the true index is being modified, return the backup value
if (rx_tail_value_not_stable) return rx_tail_value_backup;
#endif
// The true index is stable, return it
return rx_buffer.tail;
}
// (called with RX interrupts disabled)
FORCE_INLINE void store_rxd_char() {
const ring_buffer_pos_t h = rx_buffer.head,
i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// Get the tail - Nothing can alter its value while this ISR is executing, but there's
// a chance that this ISR interrupted the main process while it was updating the index.
// The backup mechanism ensures the correct value is always returned.
const ring_buffer_pos_t t = atomic_read_rx_tail();
// Get the head pointer - This ISR is the only one that modifies its value, so it's safe to read here
ring_buffer_pos_t h = rx_buffer.head;
// Get the next element
ring_buffer_pos_t i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// This must read the M_UCSRxA register before reading the received byte to detect error causes
#if ENABLED(SERIAL_STATS_DROPPED_RX)
if (TEST(M_UCSRxA, M_DORx) && !++rx_dropped_bytes) --rx_dropped_bytes;
#endif
#if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS)
if (TEST(M_UCSRxA, M_DORx) && !++rx_buffer_overruns) --rx_buffer_overruns;
#endif
#if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS)
if (TEST(M_UCSRxA, M_FEx) && !++rx_framing_errors) --rx_framing_errors;
#endif
// Read the character from the USART
uint8_t c = M_UDRx;
#if ENABLED(EMERGENCY_PARSER)
emergency_parser.update(c);
#endif
// If the character is to be stored at the index just before the tail
// (such that the head would advance to the current tail), the buffer is
// critical, so don't write the character or advance the head.
const char c = M_UDRx;
if (i != rx_buffer.tail) {
// (such that the head would advance to the current tail), the RX FIFO is
// full, so don't write the character or advance the head.
if (i != t) {
rx_buffer.buffer[h] = c;
rx_buffer.head = i;
}
else {
#if ENABLED(SERIAL_STATS_DROPPED_RX)
if (!++rx_dropped_bytes) ++rx_dropped_bytes;
#endif
h = i;
}
#if ENABLED(SERIAL_STATS_DROPPED_RX)
else if (!++rx_dropped_bytes) --rx_dropped_bytes;
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
// calculate count of bytes stored into the RX buffer
ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// Calculate count of bytes stored into the RX buffer
const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// Keep track of the maximum count of enqueued bytes
NOLESS(rx_max_enqueued, rx_count);
#endif
#if ENABLED(SERIAL_XON_XOFF)
// for high speed transfers, we can use XON/XOFF protocol to do
// software handshake and avoid overruns.
// If the last char that was sent was an XON
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XON_CHAR) {
// calculate count of bytes stored into the RX buffer
ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// Bytes stored into the RX buffer
const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// if we are above 12.5% of RX buffer capacity, send XOFF before
// we run out of RX buffer space .. We need 325 bytes @ 250kbits/s to
// let the host react and stop sending bytes. This translates to 13mS
// propagation time.
// If over 12.5% of RX buffer capacity, send XOFF before running out of
// RX buffer space .. 325 bytes @ 250kbits/s needed to let the host react
// and stop sending bytes. This translates to 13mS propagation time.
if (rx_count >= (RX_BUFFER_SIZE) / 8) {
// If TX interrupts are disabled and data register is empty,
// just write the byte to the data register and be done. This
// shortcut helps significantly improve the effective datarate
// at high (>500kbit/s) bitrates, where interrupt overhead
// becomes a slowdown.
if (!TEST(M_UCSRxB, M_UDRIEx) && TEST(M_UCSRxA, M_UDREx)) {
// Send an XOFF character
M_UDRx = XOFF_CHAR;
// clear the TXC bit -- "can be cleared by writing a one to its bit
// location". This makes sure flush() won't return until the bytes
// actually got written
SBI(M_UCSRxA, M_TXCx);
// And remember it was sent
xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
// At this point, definitely no TX interrupt was executing, since the TX ISR can't be preempted.
// Don't enable the TX interrupt here as a means to trigger the XOFF char, because if it happens
// to be in the middle of trying to disable the RX interrupt in the main program, eventually the
// enabling of the TX interrupt could be undone. The ONLY reliable thing this can do to ensure
// the sending of the XOFF char is to send it HERE AND NOW.
// About to send the XOFF char
xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
// Wait until the TX register becomes empty and send it - Here there could be a problem
// - While waiting for the TX register to empty, the RX register could receive a new
// character. This must also handle that situation!
while (!TEST(M_UCSRxA, M_UDREx)) {
if (TEST(M_UCSRxA,M_RXCx)) {
// A char arrived while waiting for the TX buffer to be empty - Receive and process it!
i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// Read the character from the USART
c = M_UDRx;
#if ENABLED(EMERGENCY_PARSER)
emergency_parser.update(c);
#endif
// If the character is to be stored at the index just before the tail
// (such that the head would advance to the current tail), the FIFO is
// full, so don't write the character or advance the head.
if (i != t) {
rx_buffer.buffer[h] = c;
h = i;
}
#if ENABLED(SERIAL_STATS_DROPPED_RX)
else if (!++rx_dropped_bytes) --rx_dropped_bytes;
#endif
}
sw_barrier();
}
else {
// TX interrupts disabled, but buffer still not empty ... or
// TX interrupts enabled. Reenable TX ints and schedule XOFF
// character to be sent
#if TX_BUFFER_SIZE > 0
SBI(M_UCSRxB, M_UDRIEx);
xon_xoff_state = XOFF_CHAR;
#else
// We are not using TX interrupts, we will have to send this manually
while (!TEST(M_UCSRxA, M_UDREx)) {/* nada */}
M_UDRx = XOFF_CHAR;
// And remember we already sent it
xon_xoff_state = XOFF_CHAR | XON_XOFF_CHAR_SENT;
#endif
M_UDRx = XOFF_CHAR;
// Clear the TXC bit -- "can be cleared by writing a one to its bit
// location". This makes sure flush() won't return until the bytes
// actually got written
SBI(M_UCSRxA, M_TXCx);
// At this point there could be a race condition between the write() function
// and this sending of the XOFF char. This interrupt could happen between the
// wait to be empty TX buffer loop and the actual write of the character. Since
// the TX buffer is full because it's sending the XOFF char, the only way to be
// sure the write() function will succeed is to wait for the XOFF char to be
// completely sent. Since an extra character could be received during the wait
// it must also be handled!
while (!TEST(M_UCSRxA, M_UDREx)) {
if (TEST(M_UCSRxA,M_RXCx)) {
// A char arrived while waiting for the TX buffer to be empty - Receive and process it!
i = (ring_buffer_pos_t)(h + 1) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// Read the character from the USART
c = M_UDRx;
#if ENABLED(EMERGENCY_PARSER)
emergency_parser.update(c);
#endif
// If the character is to be stored at the index just before the tail
// (such that the head would advance to the current tail), the FIFO is
// full, so don't write the character or advance the head.
if (i != t) {
rx_buffer.buffer[h] = c;
h = i;
}
#if ENABLED(SERIAL_STATS_DROPPED_RX)
else if (!++rx_dropped_bytes) --rx_dropped_bytes;
#endif
}
sw_barrier();
}
// At this point everything is ready. The write() function won't
// have any issues writing to the UART TX register if it needs to!
}
}
#endif // SERIAL_XON_XOFF
#if ENABLED(EMERGENCY_PARSER)
emergency_parser(c);
#endif
// Store the new head value - The main loop will retry until the value is stable
rx_buffer.head = h;
}
#if TX_BUFFER_SIZE > 0
// (called with TX irqs disabled)
FORCE_INLINE void _tx_udr_empty_irq(void) {
// If interrupts are enabled, there must be more data in the output
// buffer.
// Read positions
uint8_t t = tx_buffer.tail;
const uint8_t h = tx_buffer.head;
#if ENABLED(SERIAL_XON_XOFF)
// Do a priority insertion of an XON/XOFF char, if needed.
const uint8_t state = xon_xoff_state;
if (!(state & XON_XOFF_CHAR_SENT)) {
M_UDRx = state & XON_XOFF_CHAR_MASK;
xon_xoff_state = state | XON_XOFF_CHAR_SENT;
// If an XON char is pending to be sent, do it now
if (xon_xoff_state == XON_CHAR) {
// Send the character
M_UDRx = XON_CHAR;
// clear the TXC bit -- "can be cleared by writing a one to its bit
// location". This makes sure flush() won't return until the bytes
// actually got written
SBI(M_UCSRxA, M_TXCx);
// Remember we sent it.
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
// If nothing else to transmit, just disable TX interrupts.
if (h == t) CBI(M_UCSRxB, M_UDRIEx); // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
return;
}
else
#endif
{ // Send the next byte
const uint8_t t = tx_buffer.tail, c = tx_buffer.buffer[t];
tx_buffer.tail = (t + 1) & (TX_BUFFER_SIZE - 1);
M_UDRx = c;
// If nothing to transmit, just disable TX interrupts. This could
// happen as the result of the non atomicity of the disabling of RX
// interrupts that could end reenabling TX interrupts as a side effect.
if (h == t) {
CBI(M_UCSRxB, M_UDRIEx); // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
return;
}
// clear the TXC bit -- "can be cleared by writing a one to its bit
// location". This makes sure flush() won't return until the bytes
// actually got written
// There is something to TX, Send the next byte
const uint8_t c = tx_buffer.buffer[t];
t = (t + 1) & (TX_BUFFER_SIZE - 1);
M_UDRx = c;
tx_buffer.tail = t;
// Clear the TXC bit (by writing a one to its bit location).
// Ensures flush() won't return until the bytes are actually written/
SBI(M_UCSRxA, M_TXCx);
// Disable interrupts if the buffer is empty
if (tx_buffer.head == tx_buffer.tail)
CBI(M_UCSRxB, M_UDRIEx);
// Disable interrupts if there is nothing to transmit following this byte
if (h == t) CBI(M_UCSRxB, M_UDRIEx); // (Non-atomic, could be reenabled by the main program, but eventually this will succeed)
}
#ifdef M_USARTx_UDRE_vect
@@ -318,8 +405,8 @@
SBI(M_UCSRxB, M_RXCIEx);
#if TX_BUFFER_SIZE > 0
CBI(M_UCSRxB, M_UDRIEx);
_written = false;
#endif
_written = false;
}
void MarlinSerial::end() {
@@ -329,176 +416,179 @@
CBI(M_UCSRxB, M_UDRIEx);
}
void MarlinSerial::checkRx(void) {
if (TEST(M_UCSRxA, M_RXCx)) {
CRITICAL_SECTION_START;
store_rxd_char();
CRITICAL_SECTION_END;
}
}
int MarlinSerial::peek(void) {
CRITICAL_SECTION_START;
const int v = rx_buffer.head == rx_buffer.tail ? -1 : rx_buffer.buffer[rx_buffer.tail];
CRITICAL_SECTION_END;
return v;
const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
return h == t ? -1 : rx_buffer.buffer[t];
}
int MarlinSerial::read(void) {
int v;
CRITICAL_SECTION_START;
const ring_buffer_pos_t t = rx_buffer.tail;
if (rx_buffer.head == t)
v = -1;
else {
v = rx_buffer.buffer[t];
rx_buffer.tail = (ring_buffer_pos_t)(t + 1) & (RX_BUFFER_SIZE - 1);
const ring_buffer_pos_t h = atomic_read_rx_head();
#if ENABLED(SERIAL_XON_XOFF)
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
// Get count of bytes in the RX buffer
ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(rx_buffer.head - rx_buffer.tail) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
// When below 10% of RX buffer capacity, send XON before
// running out of RX buffer bytes
if (rx_count < (RX_BUFFER_SIZE) / 10) {
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
CRITICAL_SECTION_END; // End critical section before returning!
writeNoHandshake(XON_CHAR);
return v;
}
}
#endif
// Read the tail. Main thread owns it, so it is safe to directly read it
ring_buffer_pos_t t = rx_buffer.tail;
// If nothing to read, return now
if (h == t) return -1;
// Get the next char
const int v = rx_buffer.buffer[t];
t = (ring_buffer_pos_t)(t + 1) & (RX_BUFFER_SIZE - 1);
// Advance tail - Making sure the RX ISR will always get an stable value, even
// if it interrupts the writing of the value of that variable in the middle.
atomic_set_rx_tail(t);
#if ENABLED(SERIAL_XON_XOFF)
// If the XOFF char was sent, or about to be sent...
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
// Get count of bytes in the RX buffer
const ring_buffer_pos_t rx_count = (ring_buffer_pos_t)(h - t) & (ring_buffer_pos_t)(RX_BUFFER_SIZE - 1);
if (rx_count < (RX_BUFFER_SIZE) / 10) {
#if TX_BUFFER_SIZE > 0
// Signal we want an XON character to be sent.
xon_xoff_state = XON_CHAR;
// Enable TX ISR. Non atomic, but it will eventually enable them
SBI(M_UCSRxB, M_UDRIEx);
#else
// If not using TX interrupts, we must send the XON char now
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
while (!TEST(M_UCSRxA, M_UDREx)) sw_barrier();
M_UDRx = XON_CHAR;
#endif
}
}
CRITICAL_SECTION_END;
#endif
return v;
}
ring_buffer_pos_t MarlinSerial::available(void) {
CRITICAL_SECTION_START;
const ring_buffer_pos_t h = rx_buffer.head, t = rx_buffer.tail;
CRITICAL_SECTION_END;
const ring_buffer_pos_t h = atomic_read_rx_head(), t = rx_buffer.tail;
return (ring_buffer_pos_t)(RX_BUFFER_SIZE + h - t) & (RX_BUFFER_SIZE - 1);
}
void MarlinSerial::flush(void) {
// Don't change this order of operations. If the RX interrupt occurs between
// reading rx_buffer_head and updating rx_buffer_tail, the previous rx_buffer_head
// may be written to rx_buffer_tail, making the buffer appear full rather than empty.
CRITICAL_SECTION_START;
rx_buffer.head = rx_buffer.tail;
CRITICAL_SECTION_END;
// Set the tail to the head:
// - Read the RX head index in a safe way. (See atomic_read_rx_head.)
// - Set the tail, making sure the RX ISR will always get a stable value, even
// if it interrupts the writing of the value of that variable in the middle.
atomic_set_rx_tail(atomic_read_rx_head());
#if ENABLED(SERIAL_XON_XOFF)
// If the XOFF char was sent, or about to be sent...
if ((xon_xoff_state & XON_XOFF_CHAR_MASK) == XOFF_CHAR) {
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
writeNoHandshake(XON_CHAR);
#if TX_BUFFER_SIZE > 0
// Signal we want an XON character to be sent.
xon_xoff_state = XON_CHAR;
// Enable TX ISR. Non atomic, but it will eventually enable it.
SBI(M_UCSRxB, M_UDRIEx);
#else
// If not using TX interrupts, we must send the XON char now
xon_xoff_state = XON_CHAR | XON_XOFF_CHAR_SENT;
while (!TEST(M_UCSRxA, M_UDREx)) sw_barrier();
M_UDRx = XON_CHAR;
#endif
}
#endif
}
#if TX_BUFFER_SIZE > 0
uint8_t MarlinSerial::availableForWrite(void) {
CRITICAL_SECTION_START;
const uint8_t h = tx_buffer.head, t = tx_buffer.tail;
CRITICAL_SECTION_END;
return (uint8_t)(TX_BUFFER_SIZE + h - t) & (TX_BUFFER_SIZE - 1);
}
void MarlinSerial::write(const uint8_t c) {
#if ENABLED(SERIAL_XON_XOFF)
const uint8_t state = xon_xoff_state;
if (!(state & XON_XOFF_CHAR_SENT)) {
// Send 2 chars: XON/XOFF, then a user-specified char
writeNoHandshake(state & XON_XOFF_CHAR_MASK);
xon_xoff_state = state | XON_XOFF_CHAR_SENT;
}
#endif
writeNoHandshake(c);
}
void MarlinSerial::writeNoHandshake(const uint8_t c) {
_written = true;
CRITICAL_SECTION_START;
bool emty = (tx_buffer.head == tx_buffer.tail);
CRITICAL_SECTION_END;
// If the buffer and the data register is empty, just write the byte
// to the data register and be done. This shortcut helps
// significantly improve the effective datarate at high (>
// 500kbit/s) bitrates, where interrupt overhead becomes a slowdown.
if (emty && TEST(M_UCSRxA, M_UDREx)) {
CRITICAL_SECTION_START;
M_UDRx = c;
SBI(M_UCSRxA, M_TXCx);
CRITICAL_SECTION_END;
// If the TX interrupts are disabled and the data register
// is empty, just write the byte to the data register and
// be done. This shortcut helps significantly improve the
// effective datarate at high (>500kbit/s) bitrates, where
// interrupt overhead becomes a slowdown.
// Yes, there is a race condition between the sending of the
// XOFF char at the RX ISR, but it is properly handled there
if (!TEST(M_UCSRxB, M_UDRIEx) && TEST(M_UCSRxA, M_UDREx)) {
M_UDRx = c;
// clear the TXC bit -- "can be cleared by writing a one to its bit
// location". This makes sure flush() won't return until the bytes
// actually got written
SBI(M_UCSRxA, M_TXCx);
return;
}
const uint8_t i = (tx_buffer.head + 1) & (TX_BUFFER_SIZE - 1);
// If the output buffer is full, there's nothing for it other than to
// wait for the interrupt handler to empty it a bit
while (i == tx_buffer.tail) {
if (!TEST(SREG, SREG_I)) {
// Interrupts are disabled, so we'll have to poll the data
// register empty flag ourselves. If it is set, pretend an
// interrupt has happened and call the handler to free up
// space for us.
if (TEST(M_UCSRxA, M_UDREx))
_tx_udr_empty_irq();
}
else {
// nop, the interrupt handler will free up space for us
// If global interrupts are disabled (as the result of being called from an ISR)...
if (!ISRS_ENABLED()) {
// Make room by polling if it is possible to transmit, and do so!
while (i == tx_buffer.tail) {
// If we can transmit another byte, do it.
if (TEST(M_UCSRxA, M_UDREx)) _tx_udr_empty_irq();
// Make sure compiler rereads tx_buffer.tail
sw_barrier();
}
}
else {
// Interrupts are enabled, just wait until there is space
while (i == tx_buffer.tail) { sw_barrier(); }
}
// Store new char. head is always safe to move
tx_buffer.buffer[tx_buffer.head] = c;
{ CRITICAL_SECTION_START;
tx_buffer.head = i;
SBI(M_UCSRxB, M_UDRIEx);
CRITICAL_SECTION_END;
}
return;
tx_buffer.head = i;
// Enable TX ISR - Non atomic, but it will eventually enable TX ISR
SBI(M_UCSRxB, M_UDRIEx);
}
void MarlinSerial::flushTX(void) {
// TX
// If we have never written a byte, no need to flush. This special
// case is needed since there is no way to force the TXC (transmit
// complete) bit to 1 during initialization
if (!_written)
return;
// No bytes written, no need to flush. This special case is needed since there's
// no way to force the TXC (transmit complete) bit to 1 during initialization.
if (!_written) return;
while (TEST(M_UCSRxB, M_UDRIEx) || !TEST(M_UCSRxA, M_TXCx)) {
if (!TEST(SREG, SREG_I) && TEST(M_UCSRxB, M_UDRIEx))
// Interrupts are globally disabled, but the DR empty
// interrupt should be enabled, so poll the DR empty flag to
// prevent deadlock
// If global interrupts are disabled (as the result of being called from an ISR)...
if (!ISRS_ENABLED()) {
// Wait until everything was transmitted - We must do polling, as interrupts are disabled
while (tx_buffer.head != tx_buffer.tail || !TEST(M_UCSRxA, M_TXCx)) {
// If there is more space, send an extra character
if (TEST(M_UCSRxA, M_UDREx))
_tx_udr_empty_irq();
sw_barrier();
}
}
// If we get here, nothing is queued anymore (DRIE is disabled) and
// the hardware finished tranmission (TXC is set).
else {
// Wait until everything was transmitted
while (tx_buffer.head != tx_buffer.tail || !TEST(M_UCSRxA, M_TXCx)) sw_barrier();
}
// At this point nothing is queued anymore (DRIE is disabled) and
// the hardware finished transmission (TXC is set).
}
#else // TX_BUFFER_SIZE == 0
void MarlinSerial::write(const uint8_t c) {
#if ENABLED(SERIAL_XON_XOFF)
// Do a priority insertion of an XON/XOFF char, if needed.
const uint8_t state = xon_xoff_state;
if (!(state & XON_XOFF_CHAR_SENT)) {
writeNoHandshake(state & XON_XOFF_CHAR_MASK);
xon_xoff_state = state | XON_XOFF_CHAR_SENT;
}
#endif
writeNoHandshake(c);
}
void MarlinSerial::writeNoHandshake(uint8_t c) {
while (!TEST(M_UCSRxA, M_UDREx)) {/* nada */}
_written = true;
while (!TEST(M_UCSRxA, M_UDREx)) sw_barrier();
M_UDRx = c;
}
void MarlinSerial::flushTX(void) {
// No bytes written, no need to flush. This special case is needed since there's
// no way to force the TXC (transmit complete) bit to 1 during initialization.
if (!_written) return;
// Wait until everything was transmitted
while (!TEST(M_UCSRxA, M_TXCx)) sw_barrier();
// At this point nothing is queued anymore (DRIE is disabled) and
// the hardware finished transmission (TXC is set).
}
#endif // TX_BUFFER_SIZE == 0
/**
@@ -522,13 +612,9 @@
}
void MarlinSerial::print(long n, int base) {
if (base == 0)
write(n);
if (base == 0) write(n);
else if (base == 10) {
if (n < 0) {
print('-');
n = -n;
}
if (n < 0) { print('-'); n = -n; }
printNumber(n, 10);
}
else
@@ -646,9 +732,9 @@
// Preinstantiate
MarlinSerial customizedSerial;
#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
#endif // USE_MARLINSERIAL && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
// For AT90USB targets use the UART for BT interfacing
#if defined(USBCON) && ENABLED(BLUETOOTH)
#if !USE_MARLINSERIAL && ENABLED(BLUETOOTH)
HardwareSerial bluetoothSerial;
#endif

View File

@@ -21,16 +21,16 @@
*/
/**
MarlinSerial.h - Hardware serial library for Wiring
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
* MarlinSerial.h - Hardware serial library for Wiring
* Copyright (c) 2006 Nicholas Zambetti. All right reserved.
*
* Modified 28 September 2010 by Mark Sproul
* Modified 14 February 2016 by Andreas Hardtung (added tx buffer)
* Modified 01 October 2017 by Eduardo José Tagle (added XON/XOFF)
*/
Modified 28 September 2010 by Mark Sproul
Modified 14 February 2016 by Andreas Hardtung (added tx buffer)
*/
#ifndef MARLINSERIAL_H
#define MARLINSERIAL_H
#ifndef _MARLINSERIAL_H_
#define _MARLINSERIAL_H_
#include "MarlinConfig.h"
@@ -60,6 +60,9 @@
#define M_TXCx SERIAL_REGNAME(TXC,SERIAL_PORT,)
#define M_RXCIEx SERIAL_REGNAME(RXCIE,SERIAL_PORT,)
#define M_UDREx SERIAL_REGNAME(UDRE,SERIAL_PORT,)
#define M_FEx SERIAL_REGNAME(FE,SERIAL_PORT,)
#define M_DORx SERIAL_REGNAME(DOR,SERIAL_PORT,)
#define M_UPEx SERIAL_REGNAME(UPE,SERIAL_PORT,)
#define M_UDRIEx SERIAL_REGNAME(UDRIE,SERIAL_PORT,)
#define M_UDRx SERIAL_REGNAME(UDR,SERIAL_PORT,)
#define M_UBRRxH SERIAL_REGNAME(UBRR,SERIAL_PORT,H)
@@ -86,7 +89,7 @@
#define TX_BUFFER_SIZE 32
#endif
#ifndef USBCON
#if USE_MARLINSERIAL
#if RX_BUFFER_SIZE > 256
typedef uint16_t ring_buffer_pos_t;
@@ -98,11 +101,19 @@
extern uint8_t rx_dropped_bytes;
#endif
#if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS)
extern uint8_t rx_buffer_overruns;
#endif
#if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS)
extern uint8_t rx_framing_errors;
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
extern ring_buffer_pos_t rx_max_enqueued;
#endif
class MarlinSerial { //: public Stream
class MarlinSerial {
public:
MarlinSerial() {};
@@ -112,27 +123,25 @@
static int read(void);
static void flush(void);
static ring_buffer_pos_t available(void);
static void checkRx(void);
static void write(const uint8_t c);
#if TX_BUFFER_SIZE > 0
static uint8_t availableForWrite(void);
static void flushTX(void);
#endif
static void writeNoHandshake(const uint8_t c);
static void flushTX(void);
#if ENABLED(SERIAL_STATS_DROPPED_RX)
FORCE_INLINE static uint32_t dropped() { return rx_dropped_bytes; }
#endif
#if ENABLED(SERIAL_STATS_RX_BUFFER_OVERRUNS)
FORCE_INLINE static uint32_t buffer_overruns() { return rx_buffer_overruns; }
#endif
#if ENABLED(SERIAL_STATS_RX_FRAMING_ERRORS)
FORCE_INLINE static uint32_t framing_errors() { return rx_framing_errors; }
#endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
FORCE_INLINE static ring_buffer_pos_t rxMaxEnqueued() { return rx_max_enqueued; }
#endif
private:
static void printNumber(unsigned long, const uint8_t);
static void printFloat(double, uint8_t);
public:
FORCE_INLINE static void write(const char* str) { while (*str) write(*str++); }
FORCE_INLINE static void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
FORCE_INLINE static void print(const String& s) { for (int i = 0; i < (int)s.length(); i++) write(s[i]); }
@@ -156,15 +165,20 @@
static void println(unsigned long, int = DEC);
static void println(double, int = 2);
static void println(void);
operator bool() { return true; }
private:
static void printNumber(unsigned long, const uint8_t);
static void printFloat(double, uint8_t);
};
extern MarlinSerial customizedSerial;
#endif // !USBCON
#endif // USE_MARLINSERIAL
// Use the UART for Bluetooth in AT90USB configurations
#if defined(USBCON) && ENABLED(BLUETOOTH)
#if !USE_MARLINSERIAL && ENABLED(BLUETOOTH)
extern HardwareSerial bluetoothSerial;
#endif
#endif // MARLINSERIAL_H
#endif // _MARLINSERIAL_H_

File diff suppressed because it is too large Load Diff

View File

@@ -22,325 +22,569 @@
/**
* This module is off by default, but can be enabled to facilitate the display of
* extra debug information during code development. It assumes the existence of a
* Max7219 LED Matrix. A suitable device can be obtained on eBay similar to this:
* http://www.ebay.com/itm/191781645249 for under $2.00 including shipping.
* extra debug information during code development.
*
* Just connect up +5v and GND to give it power, then connect up the pins assigned
* Just connect up 5V and GND to give it power, then connect up the pins assigned
* in Configuration_adv.h. For example, on the Re-ARM you could use:
*
* #define MAX7219_CLK_PIN 77
* #define MAX7219_DIN_PIN 78
* #define MAX7219_LOAD_PIN 79
*
* Max7219_init() is called automatically at startup, and then there are a number of
* send() is called automatically at startup, and then there are a number of
* support functions available to control the LEDs in the 8x8 grid.
*
* void Max7219_init();
* void Max7219_PutByte(uint8_t data);
* void Max7219(uint8_t reg, uint8_t data);
* void Max7219_LED_On(uint8_t col, uint8_t row);
* void Max7219_LED_Off(uint8_t col, uint8_t row);
* void Max7219_LED_Toggle(uint8_t col, uint8_t row);
* void Max7219_Clear_Row(uint8_t row);
* void Max7219_Clear_Column(uint8_t col);
* void Max7219_Set_Row(uint8_t row, uint8_t val);
* void Max7219_Set_2_Rows(uint8_t row, uint16_t val);
* void Max7219_Set_4_Rows(uint8_t row, uint32_t val);
* void Max7219_Set_Column(uint8_t col, uint8_t val);
* void Max7219_idle_tasks();
*/
#include "MarlinConfig.h"
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_ERRORS // Disable to save 406 bytes of Program Memory
#include "Max7219_Debug_LEDs.h"
#include "planner.h"
#include "stepper.h"
#include "Marlin.h"
#include "delay.h"
static uint8_t LEDs[8] = { 0 };
Max7219 max7219;
uint8_t Max7219::led_line[MAX7219_LINES]; // = { 0 };
#define LINE_REG(Q) (max7219_reg_digit0 + ((Q) & 0x7))
#if _ROT == 0 || _ROT == 270
#define _LED_BIT(Q) (7 - ((Q) & 0x7))
#define _LED_UNIT(Q) ((Q) & ~0x7)
#else
#define _LED_BIT(Q) ((Q) & 0x7)
#define _LED_UNIT(Q) ((MAX7219_NUMBER_UNITS - 1 - ((Q) >> 3)) << 3)
#endif
#if _ROT < 180
#define _LED_IND(P,Q) (_LED_UNIT(P) + (Q))
#else
#define _LED_IND(P,Q) (_LED_UNIT(P) + (7 - ((Q) & 0x7)))
#endif
#if _ROT == 0 || _ROT == 180
#define LED_IND(X,Y) _LED_IND(X,Y)
#define LED_BIT(X,Y) _LED_BIT(X)
#elif _ROT == 90 || _ROT == 270
#define LED_IND(X,Y) _LED_IND(Y,X)
#define LED_BIT(X,Y) _LED_BIT(Y)
#endif
#define XOR_7219(X,Y) do{ led_line[LED_IND(X,Y)] ^= _BV(LED_BIT(X,Y)); }while(0)
#define SET_7219(X,Y) do{ led_line[LED_IND(X,Y)] |= _BV(LED_BIT(X,Y)); }while(0)
#define CLR_7219(X,Y) do{ led_line[LED_IND(X,Y)] &= ~_BV(LED_BIT(X,Y)); }while(0)
#define BIT_7219(X,Y) TEST(led_line[LED_IND(X,Y)], LED_BIT(X,Y))
#ifdef CPU_32_BIT
#define MS_DELAY() delayMicroseconds(5) // 32-bit processors need a delay to stabilize the signal
#define SIG_DELAY() DELAY_US(1) // Approximate a 1µs delay on 32-bit ARM
#undef CRITICAL_SECTION_START
#undef CRITICAL_SECTION_END
#define CRITICAL_SECTION_START NOOP
#define CRITICAL_SECTION_END NOOP
#else
#define MS_DELAY() NOOP
#define SIG_DELAY() DELAY_NS(188) // Delay for 0.1875µs (16MHz AVR) or 0.15µs (20MHz AVR)
#endif
void Max7219_PutByte(uint8_t data) {
CRITICAL_SECTION_START
for (uint8_t i = 8; i--;) {
MS_DELAY();
WRITE(MAX7219_CLK_PIN, LOW); // tick
MS_DELAY();
WRITE(MAX7219_DIN_PIN, (data & 0x80) ? HIGH : LOW); // send 1 or 0 based on data bit
MS_DELAY();
WRITE(MAX7219_CLK_PIN, HIGH); // tock
MS_DELAY();
data <<= 1;
}
CRITICAL_SECTION_END
}
void Max7219(const uint8_t reg, const uint8_t data) {
MS_DELAY();
CRITICAL_SECTION_START
WRITE(MAX7219_LOAD_PIN, LOW); // begin
MS_DELAY();
Max7219_PutByte(reg); // specify register
MS_DELAY();
Max7219_PutByte(data); // put data
MS_DELAY();
WRITE(MAX7219_LOAD_PIN, LOW); // and tell the chip to load the data
MS_DELAY();
WRITE(MAX7219_LOAD_PIN, HIGH);
CRITICAL_SECTION_END
MS_DELAY();
}
void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on) {
if (row > 7 || col > 7) {
SERIAL_ECHOPAIR("??? Max7219_LED_Set(", (int)row);
SERIAL_ECHOPAIR(",", (int)col);
SERIAL_ECHOLNPGM(")");
return;
}
if (TEST(LEDs[row], col) == on) return; // if LED is already on/off, leave alone
if (on) SBI(LEDs[row], col); else CBI(LEDs[row], col);
Max7219(8 - row, LEDs[row]);
}
void Max7219_LED_On(const uint8_t col, const uint8_t row) {
if (row > 7 || col > 7) {
SERIAL_ECHOPAIR("??? Max7219_LED_On(", (int)col);
SERIAL_ECHOPAIR(",", (int)row);
SERIAL_ECHOLNPGM(")");
return;
}
Max7219_LED_Set(col, row, true);
}
void Max7219_LED_Off(const uint8_t col, const uint8_t row) {
if (row > 7 || col > 7) {
SERIAL_ECHOPAIR("??? Max7219_LED_Off(", (int)row);
SERIAL_ECHOPAIR(",", (int)col);
SERIAL_ECHOLNPGM(")");
return;
}
Max7219_LED_Set(col, row, false);
}
void Max7219_LED_Toggle(const uint8_t col, const uint8_t row) {
if (row > 7 || col > 7) {
SERIAL_ECHOPAIR("??? Max7219_LED_Toggle(", (int)row);
SERIAL_ECHOPAIR(",", (int)col);
SERIAL_ECHOLNPGM(")");
return;
}
if (TEST(LEDs[row], col))
Max7219_LED_Off(col, row);
else
Max7219_LED_On(col, row);
}
void Max7219_Clear_Column(const uint8_t col) {
if (col > 7) {
SERIAL_ECHOPAIR("??? Max7219_Clear_Column(", (int)col);
SERIAL_ECHOLNPGM(")");
return;
}
LEDs[col] = 0;
Max7219(8 - col, LEDs[col]);
}
void Max7219_Clear_Row(const uint8_t row) {
if (row > 7) {
SERIAL_ECHOPAIR("??? Max7219_Clear_Row(", (int)row);
SERIAL_ECHOLNPGM(")");
return;
}
for (uint8_t c = 0; c <= 7; c++)
Max7219_LED_Off(c, row);
}
void Max7219_Set_Row(const uint8_t row, const uint8_t val) {
if (row > 7) {
SERIAL_ECHOPAIR("??? Max7219_Set_Row(", (int)row);
SERIAL_ECHOPAIR(",", (int)val);
SERIAL_ECHOLNPGM(")");
return;
}
for (uint8_t b = 0; b <= 7; b++)
if (TEST(val, b))
Max7219_LED_On(7 - b, row);
else
Max7219_LED_Off(7 - b, row);
}
void Max7219_Set_2_Rows(const uint8_t row, const uint16_t val) {
if (row > 6) {
SERIAL_ECHOPAIR("??? Max7219_Set_2_Rows(", (int)row);
SERIAL_ECHOPAIR(",", (int)val);
SERIAL_ECHOLNPGM(")");
return;
}
Max7219_Set_Row(row + 1, (val >> 8) & 0xFF);
Max7219_Set_Row(row + 0, (val ) & 0xFF);
}
void Max7219_Set_4_Rows(const uint8_t row, const uint32_t val) {
if (row > 4) {
SERIAL_ECHOPAIR("??? Max7219_Set_4_Rows(", (int)row);
SERIAL_ECHOPAIR(",", (long)val);
SERIAL_ECHOLNPGM(")");
return;
}
Max7219_Set_Row(row + 3, (val >> 24) & 0xFF);
Max7219_Set_Row(row + 2, (val >> 16) & 0xFF);
Max7219_Set_Row(row + 1, (val >> 8) & 0xFF);
Max7219_Set_Row(row + 0, (val ) & 0xFF);
}
void Max7219_Set_Column(const uint8_t col, const uint8_t val) {
if (col > 7) {
SERIAL_ECHOPAIR("??? Max7219_Column(", (int)col);
SERIAL_ECHOPAIR(",", (int)val);
SERIAL_ECHOLNPGM(")");
return;
}
LEDs[col] = val;
Max7219(8 - col, LEDs[col]);
}
void Max7219_init() {
uint8_t i, x, y;
SET_OUTPUT(MAX7219_DIN_PIN);
SET_OUTPUT(MAX7219_CLK_PIN);
OUT_WRITE(MAX7219_LOAD_PIN, HIGH);
delay(1);
//initiation of the max 7219
Max7219(max7219_reg_scanLimit, 0x07);
Max7219(max7219_reg_decodeMode, 0x00); // using an led matrix (not digits)
Max7219(max7219_reg_shutdown, 0x01); // not in shutdown mode
Max7219(max7219_reg_displayTest, 0x00); // no display test
Max7219(max7219_reg_intensity, 0x01 & 0x0F); // the first 0x0F is the value you can set
// range: 0x00 to 0x0F
for (i = 0; i <= 7; i++) { // empty registers, turn all LEDs off
LEDs[i] = 0x00;
Max7219(i + 1, 0);
}
for (x = 0; x <= 7; x++) // Do an aesthetically pleasing pattern to fully test
for (y = 0; y <= 7; y++) { // the Max7219 module and LEDs. First, turn them
Max7219_LED_On(x, y); // all on.
delay(3);
}
for (x = 0; x <= 7; x++) // Now, turn them all off.
for (y = 0; y <= 7; y++) {
Max7219_LED_Off(x, y);
delay(3); // delay() is OK here. Max7219_init() is only called from
} // setup() and nothing is running yet.
delay(150);
for (x = 8; x--;) // Now, do the same thing from the opposite direction
for (y = 0; y <= 7; y++) {
Max7219_LED_On(x, y);
delay(2);
}
for (x = 8; x--;)
for (y = 0; y <= 7; y++) {
Max7219_LED_Off(x, y);
delay(2);
}
void Max7219::error(const char * const func, const int32_t v1, const int32_t v2/*=-1*/) {
#if ENABLED(MAX7219_ERRORS)
SERIAL_ECHOPGM("??? Max7219::");
serialprintPGM(func);
SERIAL_CHAR('(');
SERIAL_ECHO(v1);
if (v2 > 0) SERIAL_ECHOPAIR(", ", v2);
SERIAL_CHAR(')');
SERIAL_EOL();
#else
UNUSED(func); UNUSED(v1); UNUSED(v2);
#endif
}
/**
* These are sample debug features to demonstrate the usage of the 8x8 LED Matrix for debug purposes.
* There is very little CPU burden added to the system by displaying information within the idle()
* task.
*
* But with that said, if your debugging can be facilitated by making calls into the library from
* other places in the code, feel free to do it. The CPU burden for a few calls to toggle an LED
* or clear a row is not very significant.
*/
void Max7219_idle_tasks() {
#if MAX7219_DEBUG_STEPPER_HEAD || MAX7219_DEBUG_STEPPER_TAIL || MAX7219_DEBUG_STEPPER_QUEUE
CRITICAL_SECTION_START
#if MAX7219_DEBUG_STEPPER_HEAD || MAX7219_DEBUG_STEPPER_QUEUE
const uint8_t head = planner.block_buffer_head;
* Flip the lowest n_bytes of the supplied bits:
* flipped(x, 1) flips the low 8 bits of x.
* flipped(x, 2) flips the low 16 bits of x.
* flipped(x, 3) flips the low 24 bits of x.
* flipped(x, 4) flips the low 32 bits of x.
*/
inline uint32_t flipped(const uint32_t bits, const uint8_t n_bytes) {
uint32_t mask = 1, outbits = 0;
for (uint8_t b = 0; b < n_bytes * 8; b++) {
outbits <<= 1;
if (bits & mask) outbits |= 1;
mask <<= 1;
}
return outbits;
}
void Max7219::noop() {
CRITICAL_SECTION_START;
SIG_DELAY();
WRITE(MAX7219_DIN_PIN, LOW);
for (uint8_t i = 16; i--;) {
SIG_DELAY();
WRITE(MAX7219_CLK_PIN, LOW);
SIG_DELAY();
SIG_DELAY();
WRITE(MAX7219_CLK_PIN, HIGH);
SIG_DELAY();
}
CRITICAL_SECTION_END;
}
void Max7219::putbyte(uint8_t data) {
CRITICAL_SECTION_START;
for (uint8_t i = 8; i--;) {
SIG_DELAY();
WRITE(MAX7219_CLK_PIN, LOW); // tick
SIG_DELAY();
WRITE(MAX7219_DIN_PIN, (data & 0x80) ? HIGH : LOW); // send 1 or 0 based on data bit
SIG_DELAY();
WRITE(MAX7219_CLK_PIN, HIGH); // tock
SIG_DELAY();
data <<= 1;
}
CRITICAL_SECTION_END;
}
void Max7219::pulse_load() {
SIG_DELAY();
WRITE(MAX7219_LOAD_PIN, LOW); // tell the chip to load the data
SIG_DELAY();
WRITE(MAX7219_LOAD_PIN, HIGH);
SIG_DELAY();
}
void Max7219::send(const uint8_t reg, const uint8_t data) {
SIG_DELAY();
CRITICAL_SECTION_START;
SIG_DELAY();
putbyte(reg); // specify register
SIG_DELAY();
putbyte(data); // put data
CRITICAL_SECTION_END;
}
// Send out a single native row of bits to all units
void Max7219::refresh_line(const uint8_t line) {
for (uint8_t u = MAX7219_NUMBER_UNITS; u--;)
send(LINE_REG(line), led_line[(u << 3) | (line & 0x7)]);
pulse_load();
}
// Send out a single native row of bits to just one unit
void Max7219::refresh_unit_line(const uint8_t line) {
for (uint8_t u = MAX7219_NUMBER_UNITS; u--;)
if (u == (line >> 3)) send(LINE_REG(line), led_line[line]); else noop();
pulse_load();
}
void Max7219::set(const uint8_t line, const uint8_t bits) {
led_line[line] = bits;
refresh_line(line);
}
#if ENABLED(MAX7219_NUMERIC)
// Draw an integer with optional leading zeros and optional decimal point
void Max7219::print(const uint8_t start, int16_t value, uint8_t size, const bool leadzero=false, bool dec=false) {
constexpr uint8_t led_numeral[10] = { 0x7E, 0x60, 0x6D, 0x79, 0x63, 0x5B, 0x5F, 0x70, 0x7F, 0x7A },
led_decimal = 0x80, led_minus = 0x01;
bool blank = false, neg = value < 0;
if (neg) value *= -1;
while (size--) {
const bool minus = neg && blank;
if (minus) neg = false;
send(
max7219_reg_digit0 + start + size,
minus ? led_minus : blank ? 0x00 : led_numeral[value % 10] | (dec ? led_decimal : 0x00)
);
pulse_load(); // tell the chips to load the clocked out data
value /= 10;
if (!value && !leadzero) blank = true;
dec = false;
}
}
// Draw a float with a decimal point and optional digits
void Max7219::print(const uint8_t start, const float value, const uint8_t pre_size, const uint8_t post_size, const bool leadzero=false) {
if (pre_size) print(start, value, pre_size, leadzero, !!post_size);
if (post_size) {
const int16_t after = ABS(value) * (10 ^ post_size);
print(start + pre_size, after, post_size, true);
}
}
#endif // MAX7219_NUMERIC
// Modify a single LED bit and send the changed line
void Max7219::led_set(const uint8_t x, const uint8_t y, const bool on) {
if (x > MAX7219_X_LEDS - 1 || y > MAX7219_Y_LEDS - 1) return error(PSTR("led_set"), x, y);
if (BIT_7219(x, y) == on) return;
XOR_7219(x, y);
refresh_line(LED_IND(x, y));
}
void Max7219::led_on(const uint8_t x, const uint8_t y) {
if (x > MAX7219_X_LEDS - 1 || y > MAX7219_Y_LEDS - 1) return error(PSTR("led_on"), x, y);
led_set(x, y, true);
}
void Max7219::led_off(const uint8_t x, const uint8_t y) {
if (x > MAX7219_X_LEDS - 1 || y > MAX7219_Y_LEDS - 1) return error(PSTR("led_off"), x, y);
led_set(x, y, false);
}
void Max7219::led_toggle(const uint8_t x, const uint8_t y) {
if (x > MAX7219_X_LEDS - 1 || y > MAX7219_Y_LEDS - 1) return error(PSTR("led_toggle"), x, y);
led_set(x, y, !BIT_7219(x, y));
}
void Max7219::send_row(const uint8_t row) {
#if _ROT == 0 || _ROT == 180
refresh_line(LED_IND(0, row));
#else
UNUSED(row);
refresh();
#endif
#if MAX7219_DEBUG_STEPPER_TAIL || MAX7219_DEBUG_STEPPER_QUEUE
const uint8_t tail = planner.block_buffer_tail;
}
void Max7219::send_column(const uint8_t col) {
#if _ROT == 90 || _ROT == 270
refresh_line(LED_IND(col, 0));
#else
UNUSED(col);
refresh();
#endif
CRITICAL_SECTION_END
}
void Max7219::clear() {
ZERO(led_line);
refresh();
}
void Max7219::fill() {
memset(led_line, 0xFF, sizeof(led_line));
refresh();
}
void Max7219::clear_row(const uint8_t row) {
if (row >= MAX7219_Y_LEDS) return error(PSTR("clear_row"), row);
for (uint8_t x = 0; x < MAX7219_X_LEDS; x++) CLR_7219(x, row);
send_row(row);
}
void Max7219::clear_column(const uint8_t col) {
if (col >= MAX7219_X_LEDS) return error(PSTR("set_column"), col);
for (uint8_t y = 0; y < MAX7219_Y_LEDS; y++) CLR_7219(col, y);
send_column(col);
}
/**
* Plot the low order bits of val to the specified row of the matrix.
* With 4 Max7219 units in the chain, it's possible to set 32 bits at once with
* one call to the function (if rotated 90° or 180°).
*/
void Max7219::set_row(const uint8_t row, const uint32_t val) {
if (row >= MAX7219_Y_LEDS) return error(PSTR("set_row"), row);
uint32_t mask = _BV32(MAX7219_X_LEDS - 1);
for (uint8_t x = 0; x < MAX7219_X_LEDS; x++) {
if (val & mask) SET_7219(x, row); else CLR_7219(x, row);
mask >>= 1;
}
send_row(row);
}
/**
* Plot the low order bits of val to the specified column of the matrix.
* With 4 Max7219 units in the chain, it's possible to set 32 bits at once with
* one call to the function (if rotated 90° or 180°).
*/
void Max7219::set_column(const uint8_t col, const uint32_t val) {
if (col >= MAX7219_X_LEDS) return error(PSTR("set_column"), col);
uint32_t mask = _BV32(MAX7219_Y_LEDS - 1);
for (uint8_t y = 0; y < MAX7219_Y_LEDS; y++) {
if (val & mask) SET_7219(col, y); else CLR_7219(col, y);
mask >>= 1;
}
send_column(col);
}
void Max7219::set_rows_16bits(const uint8_t y, uint32_t val) {
#if MAX7219_X_LEDS == 8
if (y > MAX7219_Y_LEDS - 2) return error(PSTR("set_rows_16bits"), y, val);
set_row(y + 1, val); val >>= 8;
set_row(y + 0, val);
#else // at least 16 bits on each row
if (y > MAX7219_Y_LEDS - 1) return error(PSTR("set_rows_16bits"), y, val);
set_row(y, val);
#endif
}
void Max7219::set_rows_32bits(const uint8_t y, uint32_t val) {
#if MAX7219_X_LEDS == 8
if (y > MAX7219_Y_LEDS - 4) return error(PSTR("set_rows_32bits"), y, val);
set_row(y + 3, val); val >>= 8;
set_row(y + 2, val); val >>= 8;
set_row(y + 1, val); val >>= 8;
set_row(y + 0, val);
#elif MAX7219_X_LEDS == 16
if (y > MAX7219_Y_LEDS - 2) return error(PSTR("set_rows_32bits"), y, val);
set_row(y + 1, val); val >>= 16;
set_row(y + 0, val);
#else // at least 24 bits on each row. In the 3 matrix case, just display the low 24 bits
if (y > MAX7219_Y_LEDS - 1) return error(PSTR("set_rows_32bits"), y, val);
set_row(y, val);
#endif
}
void Max7219::set_columns_16bits(const uint8_t x, uint32_t val) {
#if MAX7219_Y_LEDS == 8
if (x > MAX7219_X_LEDS - 2) return error(PSTR("set_columns_16bits"), x, val);
set_column(x + 0, val); val >>= 8;
set_column(x + 1, val);
#else // at least 16 bits in each column
if (x > MAX7219_X_LEDS - 1) return error(PSTR("set_columns_16bits"), x, val);
set_column(x, val);
#endif
}
void Max7219::set_columns_32bits(const uint8_t x, uint32_t val) {
#if MAX7219_Y_LEDS == 8
if (x > MAX7219_X_LEDS - 4) return error(PSTR("set_rows_32bits"), x, val);
set_column(x + 3, val); val >>= 8;
set_column(x + 2, val); val >>= 8;
set_column(x + 1, val); val >>= 8;
set_column(x + 0, val);
#elif MAX7219_Y_LEDS == 16
if (x > MAX7219_X_LEDS - 2) return error(PSTR("set_rows_32bits"), x, val);
set_column(x + 1, val); val >>= 16;
set_column(x + 0, val);
#else // at least 24 bits on each row. In the 3 matrix case, just display the low 24 bits
if (x > MAX7219_X_LEDS - 1) return error(PSTR("set_rows_32bits"), x, val);
set_column(x, val);
#endif
}
// Initialize the Max7219
void Max7219::register_setup() {
for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++)
send(max7219_reg_scanLimit, 0x07);
pulse_load(); // tell the chips to load the clocked out data
for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++)
send(max7219_reg_decodeMode, 0x00); // using an led matrix (not digits)
pulse_load(); // tell the chips to load the clocked out data
for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++)
send(max7219_reg_shutdown, 0x01); // not in shutdown mode
pulse_load(); // tell the chips to load the clocked out data
for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++)
send(max7219_reg_displayTest, 0x00); // no display test
pulse_load(); // tell the chips to load the clocked out data
for (uint8_t i = 0; i < MAX7219_NUMBER_UNITS; i++)
send(max7219_reg_intensity, 0x01 & 0x0F); // the first 0x0F is the value you can set
// range: 0x00 to 0x0F
pulse_load(); // tell the chips to load the clocked out data
}
#ifdef MAX7219_INIT_TEST
#if MAX7219_INIT_TEST == 2
void Max7219::spiral(const bool on, const uint16_t del) {
constexpr int8_t way[] = { 1, 0, 0, 1, -1, 0, 0, -1 };
int8_t px = 0, py = 0, dir = 0;
for (uint8_t i = MAX7219_X_LEDS * MAX7219_Y_LEDS; i--;) {
led_set(px, py, on);
delay(del);
const int8_t x = px + way[dir], y = py + way[dir + 1];
if (!WITHIN(x, 0, MAX7219_X_LEDS-1) || !WITHIN(y, 0, MAX7219_Y_LEDS-1) || BIT_7219(x, y) == on) dir = (dir + 2) & 0x7;
px += way[dir]; py += way[dir + 1];
}
}
#else
void Max7219::sweep(const int8_t dir, const uint16_t ms, const bool on) {
uint8_t x = dir > 0 ? 0 : MAX7219_X_LEDS-1;
for (uint8_t i = MAX7219_X_LEDS; i--; x += dir) {
set_column(x, on ? 0xFFFFFFFF : 0x00000000);
delay(ms);
}
}
#endif
#endif // MAX7219_INIT_TEST
void Max7219::init() {
SET_OUTPUT(MAX7219_DIN_PIN);
SET_OUTPUT(MAX7219_CLK_PIN);
OUT_WRITE(MAX7219_LOAD_PIN, HIGH);
delay(1);
register_setup();
for (uint8_t i = 0; i <= 7; i++) { // Empty registers to turn all LEDs off
led_line[i] = 0x00;
send(max7219_reg_digit0 + i, 0);
pulse_load(); // tell the chips to load the clocked out data
}
#ifdef MAX7219_INIT_TEST
#if MAX7219_INIT_TEST == 2
spiral(true, 8);
delay(150);
spiral(false, 8);
#else
// Do an aesthetically-pleasing pattern to fully test the Max7219 module and LEDs.
// Light up and turn off columns, both forward and backward.
sweep(1, 20, true);
sweep(1, 20, false);
delay(150);
sweep(-1, 20, true);
sweep(-1, 20, false);
#endif
#endif
}
/**
* This code demonstrates some simple debugging using a single 8x8 LED Matrix. If your feature could
* benefit from matrix display, add its code here. Very little processing is required, so the 7219 is
* ideal for debugging when realtime feedback is important but serial output can't be used.
*/
// Apply changes to update a marker
void Max7219::mark16(const uint8_t y, const uint8_t v1, const uint8_t v2) {
#if MAX7219_X_LEDS == 8
#if MAX7219_Y_LEDS == 8
led_off(v1 & 0x7, y + (v1 >= 8));
led_on(v2 & 0x7, y + (v2 >= 8));
#else
led_off(y, v1 & 0xF); // At least 16 LEDs down. Use a single column.
led_on(y, v2 & 0xF);
#endif
#else
led_off(v1 & 0xF, y); // At least 16 LEDs across. Use a single row.
led_on(v2 & 0xF, y);
#endif
}
// Apply changes to update a tail-to-head range
void Max7219::range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh) {
#if MAX7219_X_LEDS == 8
#if MAX7219_Y_LEDS == 8
if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF)
led_off(n & 0x7, y + (n >= 8));
if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF)
led_on(n & 0x7, y + (n >= 8));
#else // The Max7219 Y-Axis has at least 16 LED's. So use a single column
if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF)
led_off(y, n & 0xF);
if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF)
led_on(y, n & 0xF);
#endif
#else // LED matrix has at least 16 LED's on the X-Axis. Use single line of LED's
if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF)
led_off(n & 0xF, y);
if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF)
led_on(n & 0xF, y);
#endif
}
// Apply changes to update a quantity
void Max7219::quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv) {
for (uint8_t i = MIN(nv, ov); i < MAX(nv, ov); i++)
#if MAX7219_X_LEDS == 8
#if MAX7219_Y_LEDS == 8
led_set(i >> 1, y + (i & 1), nv >= ov); // single 8x8 LED matrix. Use two lines to get 16 LED's
#else
led_set(y, i, nv >= ov); // The Max7219 Y-Axis has at least 16 LED's. So use a single column
#endif
#else
led_set(i, y, nv >= ov); // LED matrix has at least 16 LED's on the X-Axis. Use single line of LED's
#endif
}
void Max7219::idle_tasks() {
#define MAX7219_USE_HEAD (defined(MAX7219_DEBUG_PLANNER_HEAD) || defined(MAX7219_DEBUG_PLANNER_QUEUE))
#define MAX7219_USE_TAIL (defined(MAX7219_DEBUG_PLANNER_TAIL) || defined(MAX7219_DEBUG_PLANNER_QUEUE))
#if MAX7219_USE_HEAD || MAX7219_USE_TAIL
CRITICAL_SECTION_START;
#if MAX7219_USE_HEAD
const uint8_t head = planner.block_buffer_head;
#endif
#if MAX7219_USE_TAIL
const uint8_t tail = planner.block_buffer_tail;
#endif
CRITICAL_SECTION_END;
#endif
#if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE)
static uint8_t refresh_cnt; // = 0
constexpr uint16_t refresh_limit = 5;
static millis_t next_blink = 0;
if (ELAPSED(millis(), next_blink)) {
Max7219_LED_Toggle(7, 7);
next_blink = millis() + 750;
const millis_t ms = millis();
const bool do_blink = ELAPSED(ms, next_blink);
#else
static uint16_t refresh_cnt; // = 0
constexpr bool do_blink = true;
constexpr uint16_t refresh_limit = 50000;
#endif
// Some Max7219 units are vulnerable to electrical noise, especially
// with long wires next to high current wires. If the display becomes
// corrupted, this will fix it within a couple seconds.
if (do_blink && ++refresh_cnt >= refresh_limit) {
refresh_cnt = 0;
register_setup();
}
#if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE)
if (do_blink) {
led_toggle(MAX7219_X_LEDS - 1, MAX7219_Y_LEDS - 1);
next_blink = ms + 1000;
}
#endif
#ifdef MAX7219_DEBUG_STEPPER_HEAD
static int16_t last_head_cnt = 0;
if (last_head_cnt != head) {
if (last_head_cnt < 8)
Max7219_LED_Off(last_head_cnt, MAX7219_DEBUG_STEPPER_HEAD);
else
Max7219_LED_Off(last_head_cnt - 8, MAX7219_DEBUG_STEPPER_HEAD + 1);
#if defined(MAX7219_DEBUG_PLANNER_HEAD) && defined(MAX7219_DEBUG_PLANNER_TAIL) && MAX7219_DEBUG_PLANNER_HEAD == MAX7219_DEBUG_PLANNER_TAIL
static int16_t last_head_cnt = 0xF, last_tail_cnt = 0xF;
if (last_head_cnt != head || last_tail_cnt != tail) {
range16(MAX7219_DEBUG_PLANNER_HEAD, last_tail_cnt, tail, last_head_cnt, head);
last_head_cnt = head;
if (head < 8)
Max7219_LED_On(head, MAX7219_DEBUG_STEPPER_HEAD);
else
Max7219_LED_On(head - 8, MAX7219_DEBUG_STEPPER_HEAD + 1);
}
#endif
#ifdef MAX7219_DEBUG_STEPPER_TAIL
static int16_t last_tail_cnt = 0;
if (last_tail_cnt != tail) {
if (last_tail_cnt < 8)
Max7219_LED_Off(last_tail_cnt, MAX7219_DEBUG_STEPPER_TAIL);
else
Max7219_LED_Off(last_tail_cnt - 8, MAX7219_DEBUG_STEPPER_TAIL + 1);
last_tail_cnt = tail;
if (tail < 8)
Max7219_LED_On(tail, MAX7219_DEBUG_STEPPER_TAIL);
else
Max7219_LED_On(tail - 8, MAX7219_DEBUG_STEPPER_TAIL + 1);
}
#else
#ifdef MAX7219_DEBUG_PLANNER_HEAD
static int16_t last_head_cnt = 0x1;
if (last_head_cnt != head) {
mark16(MAX7219_DEBUG_PLANNER_HEAD, last_head_cnt, head);
last_head_cnt = head;
}
#endif
#ifdef MAX7219_DEBUG_PLANNER_TAIL
static int16_t last_tail_cnt = 0x1;
if (last_tail_cnt != tail) {
mark16(MAX7219_DEBUG_PLANNER_TAIL, last_tail_cnt, tail);
last_tail_cnt = tail;
}
#endif
#endif
#ifdef MAX7219_DEBUG_STEPPER_QUEUE
#ifdef MAX7219_DEBUG_PLANNER_QUEUE
static int16_t last_depth = 0;
int16_t current_depth = head - tail;
if (current_depth != last_depth) { // usually, no update will be needed.
if (current_depth < 0) current_depth += BLOCK_BUFFER_SIZE;
NOMORE(current_depth, BLOCK_BUFFER_SIZE);
NOMORE(current_depth, 16); // if the BLOCK_BUFFER_SIZE is greater than 16, two lines
// of LEDs is enough to see if the buffer is draining
const uint8_t st = min(current_depth, last_depth),
en = max(current_depth, last_depth);
if (current_depth < last_depth)
for (uint8_t i = st; i <= en; i++) // clear the highest order LEDs
Max7219_LED_Off(i / 2, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
else
for (uint8_t i = st; i <= en; i++) // set the LEDs to current depth
Max7219_LED_On(i / 2, MAX7219_DEBUG_STEPPER_QUEUE + (i & 1));
const int16_t current_depth = (head - tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1) & 0xF;
if (current_depth != last_depth) {
quantity16(MAX7219_DEBUG_PLANNER_QUEUE, last_depth, current_depth);
last_depth = current_depth;
}
#endif

View File

@@ -22,41 +22,45 @@
/**
* This module is off by default, but can be enabled to facilitate the display of
* extra debug information during code development. It assumes the existence of a
* Max7219 LED Matrix. A suitable device can be obtained on eBay similar to this:
* http://www.ebay.com/itm/191781645249 for under $2.00 including shipping.
* extra debug information during code development.
*
* Just connect up +5v and GND to give it power, then connect up the pins assigned
* Just connect up 5V and GND to give it power, then connect up the pins assigned
* in Configuration_adv.h. For example, on the Re-ARM you could use:
*
* #define MAX7219_CLK_PIN 77
* #define MAX7219_DIN_PIN 78
* #define MAX7219_LOAD_PIN 79
*
* Max7219_init() is called automatically at startup, and then there are a number of
* max7219.init() is called automatically at startup, and then there are a number of
* support functions available to control the LEDs in the 8x8 grid.
*
* void Max7219_init();
* void Max7219_PutByte(uint8_t data);
* void Max7219(uint8_t reg, uint8_t data);
* void Max7219_LED_Set(uint8_t row, uint8_t col, bool on);
* void Max7219_LED_On(uint8_t col, uint8_t row);
* void Max7219_LED_Off(uint8_t col, uint8_t row);
* void Max7219_LED_Toggle(uint8_t row, uint8_t col);
* void Max7219_Clear_Row(uint8_t row);
* void Max7219_Clear_Column(uint8_t col);
* void Max7219_Set_Row(uint8_t row, uint8_t val);
* void Max7219_Set_2_Rows(uint8_t row, uint16_t val);
* void Max7219_Set_4_Rows(uint8_t row, uint32_t val);
* void Max7219_Set_Column(uint8_t col, uint8_t val);
* void Max7219_idle_tasks();
* If you are using the Max7219 matrix for firmware debug purposes in time sensitive
* areas of the code, please be aware that the orientation (rotation) of the display can
* affect the speed. The Max7219 can update a single column fairly fast. It is much
* faster to do a Max7219_Set_Column() with a rotation of 90 or 270 degrees than to do
* a Max7219_Set_Row(). The opposite is true for rotations of 0 or 180 degrees.
*/
#pragma once
#ifndef __MAX7219_DEBUG_LEDS_H__
#define __MAX7219_DEBUG_LEDS_H__
#ifndef MAX7219_ROTATE
#define MAX7219_ROTATE 0
#endif
#define _ROT ((MAX7219_ROTATE + 360) % 360)
#define MAX7219_LINES (8 * (MAX7219_NUMBER_UNITS))
#if _ROT == 0 || _ROT == 180
#define MAX7219_Y_LEDS 8
#define MAX7219_X_LEDS MAX7219_LINES
#elif _ROT == 90 || _ROT == 270
#define MAX7219_X_LEDS 8
#define MAX7219_Y_LEDS MAX7219_LINES
#else
#error "MAX7219_ROTATE must be a multiple of +/- 90°."
#endif
//
// define max7219 registers
// MAX7219 registers
//
#define max7219_reg_noop 0x00
#define max7219_reg_digit0 0x01
@@ -68,23 +72,83 @@
#define max7219_reg_digit6 0x07
#define max7219_reg_digit7 0x08
#define max7219_reg_intensity 0x0A
#define max7219_reg_displayTest 0x0F
#define max7219_reg_decodeMode 0x09
#define max7219_reg_intensity 0x0A
#define max7219_reg_scanLimit 0x0B
#define max7219_reg_shutdown 0x0C
#define max7219_reg_displayTest 0x0F
void Max7219_init();
void Max7219_PutByte(uint8_t data);
void Max7219(const uint8_t reg, const uint8_t data);
void Max7219_LED_Set(const uint8_t row, const uint8_t col, const bool on);
void Max7219_LED_On(const uint8_t row, const uint8_t col);
void Max7219_LED_Off(const uint8_t row, const uint8_t col);
void Max7219_LED_Toggle(const uint8_t row, const uint8_t col);
void Max7219_Clear_Row(const uint8_t row);
void Max7219_Clear_Column(const uint8_t col);
void Max7219_Set_Row(const uint8_t row, const uint8_t val);
void Max7219_Set_Column(const uint8_t col, const uint8_t val);
void Max7219_idle_tasks();
class Max7219 {
public:
static uint8_t led_line[MAX7219_LINES];
#endif // __MAX7219_DEBUG_LEDS_H__
Max7219() { }
static void init();
static void register_setup();
static void putbyte(uint8_t data);
static void pulse_load();
// Set a single register (e.g., a whole native row)
static void send(const uint8_t reg, const uint8_t data);
// Refresh all units
inline static void refresh() { for (uint8_t i = 0; i < 8; i++) refresh_line(i); }
// Update a single native line on all units
static void refresh_line(const uint8_t line);
// Update a single native line on just one unit
static void refresh_unit_line(const uint8_t line);
// Set a single LED by XY coordinate
static void led_set(const uint8_t x, const uint8_t y, const bool on);
static void led_on(const uint8_t x, const uint8_t y);
static void led_off(const uint8_t x, const uint8_t y);
static void led_toggle(const uint8_t x, const uint8_t y);
// Set all LEDs in a single column
static void set_column(const uint8_t col, const uint32_t val);
static void clear_column(const uint8_t col);
// Set all LEDs in a single row
static void set_row(const uint8_t row, const uint32_t val);
static void clear_row(const uint8_t row);
// 16 and 32 bit versions of Row and Column functions
// Multiple rows and columns will be used to display the value if
// the array of matrix LED's is too narrow to accomplish the goal
static void set_rows_16bits(const uint8_t y, uint32_t val);
static void set_rows_32bits(const uint8_t y, uint32_t val);
static void set_columns_16bits(const uint8_t x, uint32_t val);
static void set_columns_32bits(const uint8_t x, uint32_t val);
// Quickly clear the whole matrix
static void clear();
// Quickly fill the whole matrix
static void fill();
// Apply custom code to update the matrix
static void idle_tasks();
private:
static void error(const char * const func, const int32_t v1, const int32_t v2=-1);
static void noop();
static void set(const uint8_t line, const uint8_t bits);
static void send_row(const uint8_t row);
static void send_column(const uint8_t col);
static void mark16(const uint8_t y, const uint8_t v1, const uint8_t v2);
static void range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh);
static void quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv);
#ifdef MAX7219_INIT_TEST
#if MAX7219_INIT_TEST == 2
static void spiral(const bool on, const uint16_t del);
#else
static void sweep(const int8_t dir, const uint16_t ms, const bool on);
#endif
#endif
};
extern Max7219 max7219;

File diff suppressed because it is too large Load Diff

View File

@@ -297,7 +297,7 @@ bool Sd2Card::eraseSingleBlockEnable() {
* \return true for success, false for failure.
* The reason for failure can be determined by calling errorCode() and errorData().
*/
bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) {
bool Sd2Card::init(uint8_t sckRateID, pin_t chipSelectPin) {
errorCode_ = type_ = 0;
chipSelectPin_ = chipSelectPin;
// 16-bit init start time allows over a minute
@@ -399,27 +399,28 @@ bool Sd2Card::readBlock(uint32_t blockNumber, uint8_t* dst) {
#if ENABLED(SD_CHECK_AND_RETRY)
uint8_t retryCnt = 3;
for(;;) {
for (;;) {
if (cardCommand(CMD17, blockNumber))
error(SD_CARD_ERROR_CMD17);
else if (readData(dst, 512))
return true;
chipSelectHigh();
if (!--retryCnt) break;
chipSelectHigh();
cardCommand(CMD12, 0); // Try sending a stop command, ignore the result.
errorCode_ = 0;
}
return false;
#else
if (cardCommand(CMD17, blockNumber))
if (cardCommand(CMD17, blockNumber)) {
error(SD_CARD_ERROR_CMD17);
chipSelectHigh();
return false;
}
else
return readData(dst, 512);
#endif
chipSelectHigh();
return false;
}
/**

View File

@@ -140,7 +140,7 @@ class Sd2Card {
* \return true for success or false for failure.
*/
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
pin_t chipSelectPin = SD_CHIP_SELECT_PIN);
bool readBlock(uint32_t block, uint8_t* dst);
/**

View File

@@ -339,38 +339,38 @@ int8_t SdBaseFile::lsPrintNext(uint8_t flags, uint8_t indent) {
&& DIR_IS_FILE_OR_SUBDIR(&dir)) break;
}
// indent for dir level
for (uint8_t i = 0; i < indent; i++) MYSERIAL.write(' ');
for (uint8_t i = 0; i < indent; i++) SERIAL_CHAR(' ');
// print name
for (uint8_t i = 0; i < 11; i++) {
if (dir.name[i] == ' ')continue;
if (i == 8) {
MYSERIAL.write('.');
SERIAL_CHAR('.');
w++;
}
MYSERIAL.write(dir.name[i]);
SERIAL_CHAR(dir.name[i]);
w++;
}
if (DIR_IS_SUBDIR(&dir)) {
MYSERIAL.write('/');
SERIAL_CHAR('/');
w++;
}
if (flags & (LS_DATE | LS_SIZE)) {
while (w++ < 14) MYSERIAL.write(' ');
while (w++ < 14) SERIAL_CHAR(' ');
}
// print modify date/time if requested
if (flags & LS_DATE) {
MYSERIAL.write(' ');
SERIAL_CHAR(' ');
printFatDate(dir.lastWriteDate);
MYSERIAL.write(' ');
SERIAL_CHAR(' ');
printFatTime(dir.lastWriteTime);
}
// print size if requested
if (!DIR_IS_SUBDIR(&dir) && (flags & LS_SIZE)) {
MYSERIAL.write(' ');
MYSERIAL.print(dir.fileSize);
SERIAL_CHAR(' ');
SERIAL_ECHO(dir.fileSize);
}
MYSERIAL.println();
SERIAL_EOL();
return DIR_IS_FILE(&dir) ? 1 : 2;
}
@@ -601,7 +601,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t ofla
// search for file
while (dirFile->curPosition_ < dirFile->fileSize_) {
index = 0XF & (dirFile->curPosition_ >> 5);
index = 0xF & (dirFile->curPosition_ >> 5);
p = dirFile->readDirCache();
if (!p) return false;
@@ -705,7 +705,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag) {
return false;
}
// open cached entry
return openCachedEntry(index & 0XF, oflag);
return openCachedEntry(index & 0xF, oflag);
}
// open a cached directory entry. Assumes vol_ is initialized
@@ -775,7 +775,7 @@ bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) {
vol_ = dirFile->vol_;
while (1) {
index = 0XF & (dirFile->curPosition_ >> 5);
index = 0xF & (dirFile->curPosition_ >> 5);
// read entry into cache
p = dirFile->readDirCache();
@@ -902,11 +902,10 @@ int SdBaseFile::peek() {
return c;
}
// print uint8_t with width 2
static void print2u(uint8_t v) {
if (v < 10) MYSERIAL.write('0');
MYSERIAL.print(v, DEC);
static void print2u(const uint8_t v) {
if (v < 10) SERIAL_CHAR('0');
SERIAL_ECHO_F(v, DEC);
}
/**
@@ -927,10 +926,10 @@ static void print2u(uint8_t v) {
* \param[in] fatDate The date field from a directory entry.
*/
void SdBaseFile::printFatDate(uint16_t fatDate) {
MYSERIAL.print(FAT_YEAR(fatDate));
MYSERIAL.write('-');
SERIAL_ECHO(FAT_YEAR(fatDate));
SERIAL_CHAR('-');
print2u(FAT_MONTH(fatDate));
MYSERIAL.write('-');
SERIAL_CHAR('-');
print2u(FAT_DAY(fatDate));
}
@@ -945,9 +944,9 @@ void SdBaseFile::printFatDate(uint16_t fatDate) {
*/
void SdBaseFile::printFatTime(uint16_t fatTime) {
print2u(FAT_HOUR(fatTime));
MYSERIAL.write(':');
SERIAL_CHAR(':');
print2u(FAT_MINUTE(fatTime));
MYSERIAL.write(':');
SERIAL_CHAR(':');
print2u(FAT_SECOND(fatTime));
}
@@ -959,7 +958,7 @@ void SdBaseFile::printFatTime(uint16_t fatTime) {
bool SdBaseFile::printName() {
char name[FILENAME_LENGTH];
if (!getFilename(name)) return false;
MYSERIAL.print(name);
SERIAL_ECHO(name);
return true;
}
@@ -1055,8 +1054,9 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) {
// if not a directory file or miss-positioned return an error
if (!isDir() || (0x1F & curPosition_)) return -1;
//If we have a longFilename buffer, mark it as invalid. If we find a long filename it will be filled automaticly.
if (longFilename != NULL) longFilename[0] = '\0';
// If we have a longFilename buffer, mark it as invalid.
// If a long filename is found it will be filled automatically.
if (longFilename) longFilename[0] = '\0';
while (1) {
@@ -1066,12 +1066,15 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) {
// last entry if DIR_NAME_FREE
if (dir->name[0] == DIR_NAME_FREE) return 0;
// skip empty entries and entry for . and ..
if (dir->name[0] == DIR_NAME_DELETED || dir->name[0] == '.') continue;
// skip deleted entry and entry for . and ..
if (dir->name[0] == DIR_NAME_DELETED || dir->name[0] == '.') {
if (longFilename) longFilename[0] = '\0'; // Invalidate erased file long name, if any
continue;
}
// Fill the long filename if we have a long filename entry.
// Long filename entries are stored before the short filename.
if (longFilename != NULL && DIR_IS_LONG_NAME(dir)) {
if (longFilename && DIR_IS_LONG_NAME(dir)) {
vfat_t* VFAT = (vfat_t*)dir;
// Sanity-check the VFAT entry. The first cluster is always set to zero. And the sequence number should be higher than 0
if (VFAT->firstClusterLow == 0) {
@@ -1100,7 +1103,7 @@ dir_t* SdBaseFile::readDirCache() {
if (!isDir()) return 0;
// index of entry in cache
i = (curPosition_ >> 5) & 0XF;
i = (curPosition_ >> 5) & 0xF;
// use read to locate and cache block
if (read() < 0) return 0;
@@ -1722,8 +1725,4 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) {
return -1;
}
#if ALLOW_DEPRECATED_FUNCTIONS
void (*SdBaseFile::oldDateTime_)(uint16_t &date, uint16_t &time) = 0;
#endif
#endif // SDSUPPORT

View File

@@ -37,6 +37,8 @@
#include "SdFatConfig.h"
#include "SdVolume.h"
#include <stdint.h>
/**
* \struct filepos_t
* \brief internal type for istream
@@ -383,119 +385,6 @@ class SdBaseFile {
bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag);
bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
dir_t* readDirCache();
// Deprecated functions
#if ALLOW_DEPRECATED_FUNCTIONS
public:
/**
* \deprecated Use:
* bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
* \param[out] bgnBlock the first block address for the file.
* \param[out] endBlock the last block address for the file.
* \return true for success or false for failure.
*/
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) {
return contiguousRange(&bgnBlock, &endBlock);
}
/**
* \deprecated Use:
* bool createContiguous(SdBaseFile* dirFile, const char* path, uint32_t size)
* \param[in] dirFile The directory where the file will be created.
* \param[in] path A path with a valid DOS 8.3 file name.
* \param[in] size The desired file size.
* \return true for success or false for failure.
*/
bool createContiguous(SdBaseFile& dirFile, const char* path, uint32_t size) {
return createContiguous(&dirFile, path, size);
}
/**
* \deprecated Use:
* static void dateTimeCallback(
* void (*dateTime)(uint16_t* date, uint16_t* time));
* \param[in] dateTime The user's call back function.
*/
static void dateTimeCallback(
void (*dateTime)(uint16_t &date, uint16_t &time)) {
oldDateTime_ = dateTime;
dateTime_ = dateTime ? oldToNew : 0;
}
/**
* \deprecated Use:
* bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
* \param[in] dirFile An open SdFat instance for the directory containing the
* file to be opened.
* \param[in] path A path with a valid 8.3 DOS name for the file.
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, const char* path, uint8_t oflag) {
return open(&dirFile, path, oflag);
}
/**
* \deprecated Do not use in new apps
* \param[in] dirFile An open SdFat instance for the directory containing the
* file to be opened.
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, const char* path) {
return open(dirFile, path, O_RDWR);
}
/**
* \deprecated Use:
* bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
* \param[in] dirFile An open SdFat instance for the directory.
* \param[in] index The \a index of the directory entry for the file to be
* opened. The value for \a index is (directory file position)/32.
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) {
return open(&dirFile, index, oflag);
}
/**
* \deprecated Use: bool openRoot(SdVolume* vol);
* \param[in] vol The FAT volume containing the root directory to be opened.
* \return true for success or false for failure.
*/
bool openRoot(SdVolume& vol) { return openRoot(&vol); }
/**
* \deprecated Use: int8_t readDir(dir_t* dir);
* \param[out] dir The dir_t struct that will receive the data.
* \return bytes read for success zero for eof or -1 for failure.
*/
int8_t readDir(dir_t& dir, char* longFilename) {
return readDir(&dir, longFilename);
}
/**
* \deprecated Use:
* static uint8_t remove(SdBaseFile* dirFile, const char* path);
* \param[in] dirFile The directory that contains the file.
* \param[in] path The name of the file to be removed.
* \return true for success or false for failure.
*/
static bool remove(SdBaseFile& dirFile, const char* path) { return remove(&dirFile, path); }
private:
static void (*oldDateTime_)(uint16_t &date, uint16_t &time);
static void oldToNew(uint16_t * const date, uint16_t * const time) {
uint16_t d, t;
oldDateTime_(d, t);
*date = d;
*time = t;
}
#endif // ALLOW_DEPRECATED_FUNCTIONS
};
#endif // _SDBASEFILE_H_

View File

@@ -61,11 +61,6 @@
*/
#define ENDL_CALLS_FLUSH 0
/**
* Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
*/
#define ALLOW_DEPRECATED_FUNCTIONS 1
/**
* Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
* FAT12 has not been well tested.

View File

@@ -63,7 +63,7 @@ int SdFatUtil::FreeRam() {
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::print_P(PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) MYSERIAL.write(c);
for (uint8_t c; (c = pgm_read_byte(str)); str++) SERIAL_CHAR(c);
}
/**
@@ -72,7 +72,7 @@ void SdFatUtil::print_P(PGM_P str) {
* \param[in] pr Print object for output.
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::println_P(PGM_P str) { print_P(str); MYSERIAL.println(); }
void SdFatUtil::println_P(PGM_P str) { print_P(str); SERIAL_EOL(); }
/**
* %Print a string in flash memory to Serial.

View File

@@ -204,7 +204,7 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
index &= 0x1FF;
uint8_t tmp = value;
if (cluster & 1) {
tmp = (cacheBuffer_.data[index] & 0XF) | tmp << 4;
tmp = (cacheBuffer_.data[index] & 0xF) | tmp << 4;
}
cacheBuffer_.data[index] = tmp;
index++;

View File

@@ -48,7 +48,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
#define STRING_DISTRIBUTION_DATE "2017-12-25 12:00"
#define STRING_DISTRIBUTION_DATE "2018-07-31"
/**
* Required minimum Configuration.h and Configuration_adv.h file versions.
@@ -57,8 +57,8 @@
* but not limited to: ADD, DELETE RENAME OR REPURPOSE any directive/option on
* the configuration files.
*/
#define REQUIRED_CONFIGURATION_H_VERSION 010107
#define REQUIRED_CONFIGURATION_ADV_H_VERSION 010107
#define REQUIRED_CONFIGURATION_H_VERSION 010109
#define REQUIRED_CONFIGURATION_ADV_H_VERSION 010109
/**
* The protocol for communication to the host. Protocol indicates communication

View File

@@ -58,8 +58,10 @@
#define BOARD_K8400 79 // Velleman K8400 Controller (derived from 3Drag Controller)
#define BOARD_BAM_DICE 401 // 2PrintBeta BAM&DICE with STK drivers
#define BOARD_BAM_DICE_DUE 402 // 2PrintBeta BAM&DICE Due with STK drivers
#define BOARD_MKS_BASE 40 // MKS BASE 1.0
#define BOARD_MKS_13 47 // MKS v1.3 or 1.4 (maybe higher)
#define BOARD_MKS_BASE 40 // MKS BASE v1.0
#define BOARD_MKS_BASE_15 405 // MKS v1.5 with Allegro A4982 stepper drivers
#define BOARD_MKS_BASE_HEROIC 41 // MKS BASE 1.0 with Heroic HR4982 stepper drivers
#define BOARD_MKS_GEN_13 47 // MKS GEN v1.3 or 1.4
#define BOARD_MKS_GEN_L 53 // MKS GEN L
#define BOARD_ZRIB_V20 504 // zrib V2.0 control board (Chinese knock off RAMPS replica)
#define BOARD_FELIX2 37 // Felix 2.0+ Electronics Board (RAMPS like)
@@ -74,6 +76,9 @@
#define BOARD_RUMBA 80 // Rumba
#define BOARD_BQ_ZUM_MEGA_3D 503 // bq ZUM Mega 3D
#define BOARD_MAKEBOARD_MINI 431 // MakeBoard Mini v2.1.2 is a control board sold by MicroMake
#define BOARD_TRIGORILLA_13 343 // TriGorilla Anycubic version 1.3 based on RAMPS EFB
#define BOARD_TRIGORILLA_14 443 // TriGorilla Anycubic version 1.4 based on RAMPS EFB
#define BOARD_RAMPS_ENDER_4 243 // Creality: Ender-4, CR-8
//
// Other ATmega1280, ATmega2560
@@ -91,6 +96,8 @@
#define BOARD_RAMBO 301 // Rambo
#define BOARD_MINIRAMBO 302 // Mini-Rambo
#define BOARD_MINIRAMBO_10A 303 // Mini-Rambo 1.0a
#define BOARD_EINSY_RAMBO 304 // Einsy Rambo
#define BOARD_EINSY_RETRO 305 // Einsy Retro
#define BOARD_ELEFU_3 21 // Elefu Ra Board (v3)
#define BOARD_LEAPFROG 999 // Leapfrog
#define BOARD_MEGACONTROLLER 310 // Mega controller
@@ -114,8 +121,11 @@
#define BOARD_MELZI 63 // Melzi
#define BOARD_MELZI_MAKR3D 66 // Melzi with ATmega1284 (MaKr3d version)
#define BOARD_MELZI_CREALITY 89 // Melzi Creality3D board (for CR-10 etc)
#define BOARD_MELZI_MALYAN 92 // Melzi Malyan M150 board
#define BOARD_MELZI_TRONXY 505 // Tronxy X5S
#define BOARD_STB_11 64 // STB V1.1
#define BOARD_AZTEEG_X1 65 // Azteeg X1
#define BOARD_ANET_10 69 // Anet 1.0 (Melzi clone)
//
// Other ATmega644P, ATmega644, ATmega1284P
@@ -132,7 +142,6 @@
#define BOARD_OMCA_A 90 // Alpha OMCA board
#define BOARD_OMCA 91 // Final OMCA board
#define BOARD_SETHI 20 // Sethi 3D_1
#define BOARD_ANET_10 69 // Anet 1.0 (Melzi clone)
//
// Teensyduino - AT90USB1286, AT90USB1286P
@@ -147,6 +156,6 @@
#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: HARDWARE_MOTHERBOARD=84 make
#define BOARD_5DPRINT 88 // 5DPrint D8 Driver Board
#define MB(board) (MOTHERBOARD==BOARD_##board)
#define MB(board) (defined(BOARD_##board) && MOTHERBOARD==BOARD_##board)
#endif // __BOARDS_H

View File

@@ -104,7 +104,7 @@ class Buzzer {
* @param duration Duration of the tone in milliseconds
* @param frequency Frequency of the tone in hertz
*/
void tone(const uint16_t &duration, const uint16_t &frequency = 0) {
void tone(const uint16_t &duration, const uint16_t &frequency=0) {
while (buffer.isFull()) {
this->tick();
thermalManager.manage_heater();

View File

@@ -29,8 +29,11 @@
#include "ultralcd.h"
#include "stepper.h"
#include "language.h"
#include "printcounter.h"
#define LONGEST_FILENAME (longFilename[0] ? longFilename : filename)
#if ENABLED(POWER_LOSS_RECOVERY)
#include "power_loss_recovery.h"
#endif
CardReader::CardReader() {
#if ENABLED(SDCARD_SORT_ALPHA)
@@ -49,15 +52,13 @@ CardReader::CardReader() {
workDirDepth = 0;
ZERO(workDirParents);
autostart_stilltocheck = true; //the SD start is delayed, because otherwise the serial cannot answer fast enough to make contact with the host software.
autostart_index = 0;
// Disable autostart until card is initialized
autostart_index = -1;
//power to SD reader
#if SDPOWER > -1
OUT_WRITE(SDPOWER, HIGH);
#endif // SDPOWER
next_autostart_ms = millis() + 5000;
#endif
}
char *createFilename(char *buffer, const dir_t &p) { //buffer > 12characters
@@ -85,25 +86,25 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
uint8_t cnt = 0;
// Read the next entry from a directory
while (parent.readDir(p, longFilename) > 0) {
while (parent.readDir(&p, longFilename) > 0) {
// If the entry is a directory and the action is LS_SerialPrint
if (DIR_IS_SUBDIR(&p) && lsAction != LS_Count && lsAction != LS_GetFilename) {
// Get the short name for the item, which we know is a folder
char lfilename[FILENAME_LENGTH];
createFilename(lfilename, p);
char dosFilename[FILENAME_LENGTH];
createFilename(dosFilename, p);
// Allocate enough stack space for the full path to a folder, trailing slash, and nul
bool prepend_is_empty = (prepend[0] == '\0');
int len = (prepend_is_empty ? 1 : strlen(prepend)) + strlen(lfilename) + 1 + 1;
const bool prepend_is_empty = (!prepend || prepend[0] == '\0');
const int len = (prepend_is_empty ? 1 : strlen(prepend)) + strlen(dosFilename) + 1 + 1;
char path[len];
// Append the FOLDERNAME12/ to the passed string.
// It contains the full path to the "parent" argument.
// We now have the full path to the item in this folder.
strcpy(path, prepend_is_empty ? "/" : prepend); // root slash if prepend is empty
strcat(path, lfilename); // FILENAME_LENGTH-1 characters maximum
strcat(path, dosFilename); // FILENAME_LENGTH-1 characters maximum
strcat(path, "/"); // 1 character
// Serial.print(path);
@@ -111,11 +112,11 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
// Get a new directory object using the full path
// and dive recursively into it.
SdFile dir;
if (!dir.open(parent, lfilename, O_READ)) {
if (!dir.open(&parent, dosFilename, O_READ)) {
if (lsAction == LS_SerialPrint) {
SERIAL_ECHO_START();
SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR);
SERIAL_ECHOLN(lfilename);
SERIAL_ECHOLN(dosFilename);
}
}
lsDive(path, dir);
@@ -140,7 +141,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
case LS_SerialPrint:
createFilename(filename, p);
SERIAL_PROTOCOL(prepend);
if (prepend) SERIAL_PROTOCOL(prepend);
SERIAL_PROTOCOL(filename);
SERIAL_PROTOCOLCHAR(' ');
SERIAL_PROTOCOLLN(p.fileSize);
@@ -163,7 +164,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
void CardReader::ls() {
lsAction = LS_SerialPrint;
root.rewind();
lsDive("", root);
lsDive(NULL, root);
}
#if ENABLED(LONG_FILENAME_HOST_SUPPORT)
@@ -198,7 +199,7 @@ void CardReader::ls() {
// Find the item, setting the long filename
diveDir.rewind();
lsDive("", diveDir, segment);
lsDive(NULL, diveDir, segment);
// Print /LongNamePart to serial output
SERIAL_PROTOCOLCHAR('/');
@@ -211,7 +212,7 @@ void CardReader::ls() {
// Open the sub-item as the new dive parent
SdFile dir;
if (!dir.open(diveDir, segment, O_READ)) {
if (!dir.open(&diveDir, segment, O_READ)) {
SERIAL_EOL();
SERIAL_ECHO_START();
SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR);
@@ -229,6 +230,28 @@ void CardReader::ls() {
#endif // LONG_FILENAME_HOST_SUPPORT
/**
* Echo the DOS 8.3 filename (and long filename, if any)
*/
void CardReader::printFilename() {
if (file.isOpen()) {
char dosFilename[FILENAME_LENGTH];
file.getFilename(dosFilename);
SERIAL_ECHO(dosFilename);
#if ENABLED(LONG_FILENAME_HOST_SUPPORT)
getfilename(0, dosFilename);
if (longFilename[0]) {
SERIAL_ECHO(' ');
SERIAL_ECHO(longFilename);
}
#endif
}
else
SERIAL_ECHOPGM("(no file)");
SERIAL_EOL();
}
void CardReader::initsd() {
cardOK = false;
if (root.isOpen()) root.close();
@@ -237,16 +260,16 @@ void CardReader::initsd() {
#define SPI_SPEED SPI_FULL_SPEED
#endif
if (!card.init(SPI_SPEED, SDSS)
if (!sd2card.init(SPI_SPEED, SDSS)
#if defined(LCD_SDSS) && (LCD_SDSS != SDSS)
&& !card.init(SPI_SPEED, LCD_SDSS)
&& !sd2card.init(SPI_SPEED, LCD_SDSS)
#endif
) {
//if (!card.init(SPI_HALF_SPEED,SDSS))
//if (!sd2card.init(SPI_HALF_SPEED,SDSS))
SERIAL_ECHO_START();
SERIAL_ECHOLNPGM(MSG_SD_INIT_FAIL);
}
else if (!volume.init(&card)) {
else if (!volume.init(&sd2card)) {
SERIAL_ERROR_START();
SERIAL_ERRORLNPGM(MSG_SD_VOL_INIT_FAIL);
}
@@ -262,17 +285,6 @@ void CardReader::initsd() {
setroot();
}
void CardReader::setroot() {
/*if (!workDir.openRoot(&volume)) {
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
}*/
workDir = root;
curDir = &workDir;
#if ENABLED(SDCARD_SORT_ALPHA)
presort();
#endif
}
void CardReader::release() {
sdprinting = false;
cardOK = false;
@@ -282,27 +294,37 @@ void CardReader::openAndPrintFile(const char *name) {
char cmd[4 + strlen(name) + 1]; // Room for "M23 ", filename, and null
sprintf_P(cmd, PSTR("M23 %s"), name);
for (char *c = &cmd[4]; *c; c++) *c = tolower(*c);
enqueue_and_echo_command(cmd);
enqueue_and_echo_command_now(cmd);
enqueue_and_echo_commands_P(PSTR("M24"));
}
void CardReader::startFileprint() {
if (cardOK) {
sdprinting = true;
#if ENABLED(SDCARD_SORT_ALPHA)
#if SD_RESORT
flush_presort();
#endif
}
}
void CardReader::stopSDPrint() {
void CardReader::stopSDPrint(
#if SD_RESORT
const bool re_sort/*=false*/
#endif
) {
#if ENABLED(ADVANCED_PAUSE_FEATURE)
did_pause_print = 0;
#endif
sdprinting = false;
if (isFileOpen()) file.close();
#if SD_RESORT
if (re_sort) presort();
#endif
}
void CardReader::openLogFile(char* name) {
void CardReader::openLogFile(char * const path) {
logging = true;
openFile(name, false);
openFile(path, false);
}
void appendAtom(SdFile &file, char *& dst, uint8_t &cnt) {
@@ -325,7 +347,7 @@ void CardReader::getAbsFilename(char *t) {
*t = '\0';
}
void CardReader::openFile(char* name, const bool read, const bool subcall/*=false*/) {
void CardReader::openFile(char * const path, const bool read, const bool subcall/*=false*/) {
if (!cardOK) return;
@@ -335,7 +357,7 @@ void CardReader::openFile(char* name, const bool read, const bool subcall/*=fals
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
SERIAL_ERROR_START();
SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
SERIAL_ERRORLN((int)SD_PROCEDURE_DEPTH);
kill(PSTR(MSG_KILLED));
return;
}
@@ -345,7 +367,7 @@ void CardReader::openFile(char* name, const bool read, const bool subcall/*=fals
filespos[file_subcall_ctr] = sdpos;
SERIAL_ECHO_START();
SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name);
SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", path);
SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
SERIAL_ECHOLNPAIR("\" pos", sdpos);
file_subcall_ctr++;
@@ -366,49 +388,14 @@ void CardReader::openFile(char* name, const bool read, const bool subcall/*=fals
SERIAL_ECHO_START();
SERIAL_ECHOPGM("Now ");
serialprintPGM(doing == 1 ? PSTR("doing") : PSTR("fresh"));
SERIAL_ECHOLNPAIR(" file: ", name);
SERIAL_ECHOLNPAIR(" file: ", path);
}
stopSDPrint();
SdFile myDir;
curDir = &root;
char *fname = name;
char *dirname_start, *dirname_end;
if (name[0] == '/') {
dirname_start = &name[1];
while (dirname_start != NULL) {
dirname_end = strchr(dirname_start, '/');
//SERIAL_ECHOPGM("start:");SERIAL_ECHOLN((int)(dirname_start - name));
//SERIAL_ECHOPGM("end :");SERIAL_ECHOLN((int)(dirname_end - name));
if (dirname_end != NULL && dirname_end > dirname_start) {
char subdirname[FILENAME_LENGTH];
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
subdirname[dirname_end - dirname_start] = '\0';
if (!myDir.open(curDir, subdirname, O_READ)) {
SERIAL_PROTOCOLPGM(MSG_SD_OPEN_FILE_FAIL);
SERIAL_PROTOCOL(subdirname);
SERIAL_PROTOCOLCHAR('.');
return;
}
else {
//SERIAL_ECHOLNPGM("dive ok");
}
curDir = &myDir;
dirname_start = dirname_end + 1;
}
else { // the remainder after all /fsa/fdsa/ is the filename
fname = dirname_start;
//SERIAL_ECHOLNPGM("remainder");
//SERIAL_ECHOLN(fname);
break;
}
}
}
else
curDir = &workDir; // Relative paths start in current directory
SdFile *curDir;
const char * const fname = diveToFile(curDir, path, false);
if (!fname) return;
if (read) {
if (file.open(curDir, fname, O_READ)) {
@@ -417,8 +404,12 @@ void CardReader::openFile(char* name, const bool read, const bool subcall/*=fals
SERIAL_PROTOCOLPAIR(MSG_SD_FILE_OPENED, fname);
SERIAL_PROTOCOLLNPAIR(MSG_SD_SIZE, filesize);
SERIAL_PROTOCOLLNPGM(MSG_SD_FILE_SELECTED);
getfilename(0, fname);
lcd_setstatus(longFilename[0] ? longFilename : fname);
//if (longFilename[0]) {
// SERIAL_PROTOCOLPAIR(MSG_SD_FILE_LONG_NAME, longFilename);
//}
}
else {
SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, fname);
@@ -434,7 +425,7 @@ void CardReader::openFile(char* name, const bool read, const bool subcall/*=fals
}
else {
saving = true;
SERIAL_PROTOCOLLNPAIR(MSG_SD_WRITE_TO_FILE, name);
SERIAL_PROTOCOLLNPAIR(MSG_SD_WRITE_TO_FILE, path);
lcd_setstatus(fname);
}
}
@@ -445,40 +436,9 @@ void CardReader::removeFile(const char * const name) {
stopSDPrint();
SdFile myDir;
curDir = &root;
const char *fname = name;
char *dirname_start, *dirname_end;
if (name[0] == '/') {
dirname_start = strchr(name, '/') + 1;
while (dirname_start != NULL) {
dirname_end = strchr(dirname_start, '/');
//SERIAL_ECHOPGM("start:");SERIAL_ECHOLN((int)(dirname_start - name));
//SERIAL_ECHOPGM("end :");SERIAL_ECHOLN((int)(dirname_end - name));
if (dirname_end != NULL && dirname_end > dirname_start) {
char subdirname[FILENAME_LENGTH];
strncpy(subdirname, dirname_start, dirname_end - dirname_start);
subdirname[dirname_end - dirname_start] = 0;
SERIAL_ECHOLN(subdirname);
if (!myDir.open(curDir, subdirname, O_READ)) {
SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, subdirname);
SERIAL_PROTOCOLCHAR('.');
SERIAL_EOL();
return;
}
curDir = &myDir;
dirname_start = dirname_end + 1;
}
else {
fname = dirname_start;
break;
}
}
}
else // Relative paths are rooted in the current directory
curDir = &workDir;
SdFile *curDir;
const char * const fname = diveToFile(curDir, name, false);
if (!fname) return;
if (file.remove(curDir, fname)) {
SERIAL_PROTOCOLPGM("File deleted:");
@@ -496,7 +456,7 @@ void CardReader::removeFile(const char * const name) {
}
void CardReader::getStatus() {
if (cardOK) {
if (cardOK && sdprinting) {
SERIAL_PROTOCOLPGM(MSG_SD_PRINTING_BYTE);
SERIAL_PROTOCOL(sdpos);
SERIAL_PROTOCOLCHAR('/');
@@ -526,40 +486,46 @@ void CardReader::write_command(char *buf) {
}
}
void CardReader::checkautostart(bool force) {
if (!force && (!autostart_stilltocheck || PENDING(millis(), next_autostart_ms)))
return;
//
// Run the next autostart file. Called:
// - On boot after successful card init
// - After finishing the previous autostart file
// - From the LCD command to run the autostart file
//
autostart_stilltocheck = false;
void CardReader::checkautostart() {
if (!cardOK) {
initsd();
if (!cardOK) return; // fail
}
if (autostart_index < 0 || sdprinting) return;
char autoname[10];
sprintf_P(autoname, PSTR("auto%i.g"), autostart_index);
for (int8_t i = 0; i < (int8_t)strlen(autoname); i++) autoname[i] = tolower(autoname[i]);
if (!cardOK) initsd();
dir_t p;
root.rewind();
bool found = false;
while (root.readDir(p, NULL) > 0) {
for (int8_t i = (int8_t)strlen((char*)p.name); i--;) p.name[i] = tolower(p.name[i]);
if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
openAndPrintFile(autoname);
found = true;
if (cardOK
#if ENABLED(POWER_LOSS_RECOVERY)
&& !jobRecoverFileExists() // Don't run auto#.g when a resume file exists
#endif
) {
char autoname[10];
sprintf_P(autoname, PSTR("auto%i.g"), int(autostart_index));
dir_t p;
root.rewind();
while (root.readDir(&p, NULL) > 0) {
for (int8_t i = (int8_t)strlen((char*)p.name); i--;) p.name[i] = tolower(p.name[i]);
if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
openAndPrintFile(autoname);
autostart_index++;
return;
}
}
}
if (!found)
autostart_index = -1;
else
autostart_index++;
autostart_index = -1;
}
void CardReader::closefile(bool store_location) {
void CardReader::beginautostart() {
autostart_index = 0;
setroot();
}
void CardReader::closefile(const bool store_location) {
file.sync();
file.close();
saving = logging = false;
@@ -572,6 +538,7 @@ void CardReader::closefile(bool store_location) {
/**
* Get the name of a file in the current directory by index
* with optional name to match.
*/
void CardReader::getfilename(uint16_t nr, const char * const match/*=NULL*/) {
#if ENABLED(SDSORT_CACHE_NAMES)
@@ -588,35 +555,59 @@ void CardReader::getfilename(uint16_t nr, const char * const match/*=NULL*/) {
return;
}
#endif // SDSORT_CACHE_NAMES
curDir = &workDir;
lsAction = LS_GetFilename;
nrFile_index = nr;
curDir->rewind();
lsDive("", *curDir, match);
workDir.rewind();
lsDive(NULL, workDir, match);
}
uint16_t CardReader::getnrfilenames() {
curDir = &workDir;
lsAction = LS_Count;
nrFiles = 0;
curDir->rewind();
lsDive("", *curDir);
workDir.rewind();
lsDive(NULL, workDir);
//SERIAL_ECHOLN(nrFiles);
return nrFiles;
}
/**
* Dive to the given file path, with optional echo.
* On exit set curDir and return the name part of the path.
* A NULL result indicates an unrecoverable error.
*/
const char* CardReader::diveToFile(SdFile*& curDir, const char * const path, const bool echo) {
SdFile myDir;
if (path[0] != '/') { curDir = &workDir; return path; }
curDir = &root;
const char *dirname_start = &path[1];
while (dirname_start) {
char * const dirname_end = strchr(dirname_start, '/');
if (dirname_end <= dirname_start) break;
const uint8_t len = dirname_end - dirname_start;
char dosSubdirname[len + 1];
strncpy(dosSubdirname, dirname_start, len);
dosSubdirname[len] = 0;
if (echo) SERIAL_ECHOLN(dosSubdirname);
if (!myDir.open(curDir, dosSubdirname, O_READ)) {
SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, dosSubdirname);
SERIAL_PROTOCOLCHAR('.');
SERIAL_EOL();
return NULL;
}
curDir = &myDir;
dirname_start = dirname_end + 1;
}
return dirname_start;
}
void CardReader::chdir(const char * relpath) {
SdFile newDir;
SdFile *parent = &root;
SdFile *parent = workDir.isOpen() ? &workDir : &root;
if (workDir.isOpen()) parent = &workDir;
if (!newDir.open(*parent, relpath, O_READ)) {
SERIAL_ECHO_START();
SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
SERIAL_ECHOLN(relpath);
}
else {
if (newDir.open(parent, relpath, O_READ)) {
workDir = newDir;
if (workDirDepth < MAX_DIR_DEPTH)
workDirParents[workDirDepth++] = workDir;
@@ -624,6 +615,11 @@ void CardReader::chdir(const char * relpath) {
presort();
#endif
}
else {
SERIAL_ECHO_START();
SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
SERIAL_ECHOLN(relpath);
}
}
int8_t CardReader::updir() {
@@ -636,6 +632,16 @@ int8_t CardReader::updir() {
return workDirDepth;
}
void CardReader::setroot() {
/*if (!workDir.openRoot(&volume)) {
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
}*/
workDir = root;
#if ENABLED(SDCARD_SORT_ALPHA)
presort();
#endif
}
#if ENABLED(SDCARD_SORT_ALPHA)
/**
@@ -660,14 +666,14 @@ int8_t CardReader::updir() {
*/
void CardReader::presort() {
// Throw away old sort index
flush_presort();
// Sorting may be turned off
#if ENABLED(SDSORT_GCODE)
if (!sort_alpha) return;
#endif
// Throw away old sort index
flush_presort();
// If there are files, sort up to the limit
uint16_t fileCnt = getnrfilenames();
if (fileCnt > 0) {
@@ -723,7 +729,7 @@ int8_t CardReader::updir() {
getfilename(i);
#if ENABLED(SDSORT_DYNAMIC_RAM)
// Use dynamic method to copy long filename
sortnames[i] = strdup(LONGEST_FILENAME);
sortnames[i] = strdup(longest_filename());
#if ENABLED(SDSORT_CACHE_NAMES)
// When caching also store the short name, since
// we're replacing the getfilename() behavior.
@@ -732,10 +738,10 @@ int8_t CardReader::updir() {
#else
// Copy filenames into the static array
#if SORTED_LONGNAME_MAXLEN != LONG_FILENAME_LENGTH
strncpy(sortnames[i], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
strncpy(sortnames[i], longest_filename(), SORTED_LONGNAME_MAXLEN);
sortnames[i][SORTED_LONGNAME_MAXLEN - 1] = '\0';
#else
strncpy(sortnames[i], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
strncpy(sortnames[i], longest_filename(), SORTED_LONGNAME_MAXLEN);
#endif
#if ENABLED(SDSORT_CACHE_NAMES)
strcpy(sortshort[i], filename);
@@ -783,12 +789,12 @@ int8_t CardReader::updir() {
// throughout the loop. Slow if there are many.
#if DISABLED(SDSORT_USES_RAM)
getfilename(o1);
strcpy(name1, LONGEST_FILENAME); // save (or getfilename below will trounce it)
strcpy(name1, longest_filename()); // save (or getfilename below will trounce it)
#if HAS_FOLDER_SORTING
bool dir1 = filenameIsDir;
#endif
getfilename(o2);
char *name2 = LONGEST_FILENAME; // use the string in-place
char *name2 = longest_filename(); // use the string in-place
#endif // !SDSORT_USES_RAM
// Sort the current pair according to settings.
@@ -826,7 +832,7 @@ int8_t CardReader::updir() {
getfilename(0);
#if ENABLED(SDSORT_DYNAMIC_RAM)
sortnames = new char*[1];
sortnames[0] = strdup(LONGEST_FILENAME); // malloc
sortnames[0] = strdup(longest_filename()); // malloc
#if ENABLED(SDSORT_CACHE_NAMES)
sortshort = new char*[1];
sortshort[0] = strdup(filename); // malloc
@@ -834,10 +840,10 @@ int8_t CardReader::updir() {
isDir = new uint8_t[1];
#else
#if SORTED_LONGNAME_MAXLEN != LONG_FILENAME_LENGTH
strncpy(sortnames[0], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
strncpy(sortnames[0], longest_filename(), SORTED_LONGNAME_MAXLEN);
sortnames[0][SORTED_LONGNAME_MAXLEN - 1] = '\0';
#else
strncpy(sortnames[0], LONGEST_FILENAME, SORTED_LONGNAME_MAXLEN);
strncpy(sortnames[0], longest_filename(), SORTED_LONGNAME_MAXLEN);
#endif
#if ENABLED(SDSORT_CACHE_NAMES)
strcpy(sortshort[0], filename);
@@ -881,7 +887,7 @@ uint16_t CardReader::get_num_Files() {
}
void CardReader::printingHasFinished() {
stepper.synchronize();
planner.synchronize();
file.close();
if (file_subcall_ctr > 0) { // Heading up to a parent file that called current as a procedure.
file_subcall_ctr--;
@@ -891,8 +897,13 @@ void CardReader::printingHasFinished() {
}
else {
sdprinting = false;
#if ENABLED(POWER_LOSS_RECOVERY)
removeJobRecoveryFile();
#endif
#if ENABLED(SD_FINISHED_STEPPERRELEASE) && defined(SD_FINISHED_RELEASECOMMAND)
stepper.cleaning_buffer_counter = 1; // The command will fire from the Stepper ISR
planner.finish_and_disable();
#endif
print_job_timer.stop();
if (print_job_timer.duration() > 60)
@@ -900,11 +911,77 @@ void CardReader::printingHasFinished() {
#if ENABLED(SDCARD_SORT_ALPHA)
presort();
#endif
#if ENABLED(ULTRA_LCD) && ENABLED(LCD_SET_PROGRESS_MANUALLY)
progress_bar_percent = 0;
#endif
#if ENABLED(SD_REPRINT_LAST_SELECTED_FILE)
lcd_reselect_last_file();
#endif
}
}
#if ENABLED(AUTO_REPORT_SD_STATUS)
uint8_t CardReader::auto_report_sd_interval = 0;
millis_t CardReader::next_sd_report_ms;
void CardReader::auto_report_sd_status() {
millis_t current_ms = millis();
if (auto_report_sd_interval && ELAPSED(current_ms, next_sd_report_ms)) {
next_sd_report_ms = current_ms + 1000UL * auto_report_sd_interval;
getStatus();
}
}
#endif // AUTO_REPORT_SD_STATUS
#if ENABLED(POWER_LOSS_RECOVERY)
char job_recovery_file_name[4] = "bin";
void CardReader::openJobRecoveryFile(const bool read) {
if (!cardOK) return;
if (jobRecoveryFile.isOpen()) return;
if (!jobRecoveryFile.open(&root, job_recovery_file_name, read ? O_READ : O_CREAT | O_WRITE | O_TRUNC | O_SYNC)) {
SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, job_recovery_file_name);
SERIAL_PROTOCOLCHAR('.');
SERIAL_EOL();
}
else if (!read)
SERIAL_PROTOCOLLNPAIR(MSG_SD_WRITE_TO_FILE, job_recovery_file_name);
}
void CardReader::closeJobRecoveryFile() { jobRecoveryFile.close(); }
bool CardReader::jobRecoverFileExists() {
const bool exists = jobRecoveryFile.open(&root, job_recovery_file_name, O_READ);
if (exists) jobRecoveryFile.close();
return exists;
}
int16_t CardReader::saveJobRecoveryInfo() {
jobRecoveryFile.seekSet(0);
const int16_t ret = jobRecoveryFile.write(&job_recovery_info, sizeof(job_recovery_info));
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
if (ret == -1) SERIAL_PROTOCOLLNPGM("Power-loss file write failed.");
#endif
return ret;
}
int16_t CardReader::loadJobRecoveryInfo() {
return jobRecoveryFile.read(&job_recovery_info, sizeof(job_recovery_info));
}
void CardReader::removeJobRecoveryFile() {
job_recovery_info.valid_head = job_recovery_info.valid_foot = job_recovery_commands_count = 0;
if (jobRecoverFileExists()) {
closefile();
removeFile(job_recovery_file_name);
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
SERIAL_PROTOCOLPGM("Power-loss file delete");
serialprintPGM(jobRecoverFileExists() ? PSTR(" failed.\n") : PSTR("d.\n"));
#endif
}
}
#endif // POWER_LOSS_RECOVERY
#endif // SDSUPPORT

View File

@@ -27,11 +27,11 @@
#if ENABLED(SDSUPPORT)
#define SD_RESORT ENABLED(SDCARD_SORT_ALPHA) && ENABLED(SDSORT_DYNAMIC_RAM)
#define MAX_DIR_DEPTH 10 // Maximum folder depth
#include "SdFile.h"
#include "types.h"
#include "enum.h"
class CardReader {
public:
@@ -39,22 +39,25 @@ public:
void initsd();
void write_command(char *buf);
// Files auto[0-9].g on the sd card are performed in sequence.
// This is to delay autostart and hence the initialisation of
// the sd card to some seconds after the normal init, so the
// device is available soon after a reset.
void checkautostart(bool x);
void openFile(char* name, const bool read, const bool subcall=false);
void openLogFile(char* name);
void beginautostart();
void checkautostart();
void openFile(char * const path, const bool read, const bool subcall=false);
void openLogFile(char * const path);
void removeFile(const char * const name);
void closefile(bool store_location=false);
void closefile(const bool store_location=false);
void release();
void openAndPrintFile(const char *name);
void startFileprint();
void stopSDPrint();
void stopSDPrint(
#if SD_RESORT
const bool re_sort=false
#endif
);
void getStatus();
void printingHasFinished();
void printFilename();
#if ENABLED(LONG_FILENAME_HOST_SUPPORT)
void printLongPath(char *path);
@@ -70,6 +73,8 @@ public:
int8_t updir();
void setroot();
const char* diveToFile(SdFile*& curDir, const char * const path, const bool echo);
uint16_t get_num_Files();
#if ENABLED(SDCARD_SORT_ALPHA)
@@ -82,20 +87,41 @@ public:
#endif
#endif
#if ENABLED(POWER_LOSS_RECOVERY)
void openJobRecoveryFile(const bool read);
void closeJobRecoveryFile();
bool jobRecoverFileExists();
int16_t saveJobRecoveryInfo();
int16_t loadJobRecoveryInfo();
void removeJobRecoveryFile();
#endif
FORCE_INLINE void pauseSDPrint() { sdprinting = false; }
FORCE_INLINE bool isFileOpen() { return file.isOpen(); }
FORCE_INLINE bool eof() { return sdpos >= filesize; }
FORCE_INLINE int16_t get() { sdpos = file.curPosition(); return (int16_t)file.read(); }
FORCE_INLINE void setIndex(long index) { sdpos = index; file.seekSet(index); }
FORCE_INLINE void setIndex(const uint32_t index) { sdpos = index; file.seekSet(index); }
FORCE_INLINE uint32_t getIndex() { return sdpos; }
FORCE_INLINE uint8_t percentDone() { return (isFileOpen() && filesize) ? sdpos / ((filesize + 99) / 100) : 0; }
FORCE_INLINE char* getWorkDirName() { workDir.getFilename(filename); return filename; }
#if ENABLED(AUTO_REPORT_SD_STATUS)
void auto_report_sd_status(void);
FORCE_INLINE void set_auto_report_interval(uint8_t v) {
NOMORE(v, 60);
auto_report_sd_interval = v;
next_sd_report_ms = millis() + 1000UL * v;
}
#endif
FORCE_INLINE char* longest_filename() { return longFilename[0] ? longFilename : filename; }
public:
bool saving, logging, sdprinting, cardOK, filenameIsDir;
char filename[FILENAME_LENGTH], longFilename[LONG_FILENAME_LENGTH];
int autostart_index;
int8_t autostart_index;
private:
SdFile root, *curDir, workDir, workDirParents[MAX_DIR_DEPTH];
SdFile root, workDir, workDirParents[MAX_DIR_DEPTH];
uint8_t workDirDepth;
// Sort files and folders alphabetically.
@@ -148,10 +174,14 @@ private:
#endif // SDCARD_SORT_ALPHA
Sd2Card card;
Sd2Card sd2card;
SdVolume volume;
SdFile file;
#if ENABLED(POWER_LOSS_RECOVERY)
SdFile jobRecoveryFile;
#endif
#define SD_PROCEDURE_DEPTH 1
#define MAXPATHNAMELENGTH (FILENAME_LENGTH*MAX_DIR_DEPTH + MAX_DIR_DEPTH + 1)
uint8_t file_subcall_ctr;
@@ -159,9 +189,6 @@ private:
char proc_filenames[SD_PROCEDURE_DEPTH][MAXPATHNAMELENGTH];
uint32_t filesize, sdpos;
millis_t next_autostart_ms;
bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
LsAction lsAction; //stored for recursion.
uint16_t nrFiles; //counter for the files in the current directory and recycled as position counter for getting the nrFiles'th name in the directory.
char* diveDirName;
@@ -170,6 +197,11 @@ private:
#if ENABLED(SDCARD_SORT_ALPHA)
void flush_presort();
#endif
#if ENABLED(AUTO_REPORT_SD_STATUS)
static uint8_t auto_report_sd_interval;
static millis_t next_sd_report_ms;
#endif
};
#if PIN_EXISTS(SD_DETECT)

File diff suppressed because it is too large Load Diff

View File

@@ -29,17 +29,34 @@ class MarlinSettings {
public:
MarlinSettings() { }
static uint16_t datasize();
static void reset();
static bool save();
static bool save(); // Return 'true' if data was saved
FORCE_INLINE static bool init_eeprom() {
reset();
#if ENABLED(EEPROM_SETTINGS)
const bool success = save();
#if ENABLED(EEPROM_CHITCHAT)
if (success) report();
#endif
return success;
#else
return true;
#endif
}
#if ENABLED(EEPROM_SETTINGS)
static bool load();
static bool load(); // Return 'true' if data was loaded ok
static bool validate(); // Return 'true' if EEPROM data is ok
#if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system
// That can store is enabled
FORCE_INLINE static int16_t get_start_of_meshes() { return meshes_begin; }
FORCE_INLINE static int16_t get_end_of_meshes() { return meshes_end; }
static uint16_t meshes_start_index();
FORCE_INLINE static uint16_t meshes_end_index() { return meshes_end; }
static uint16_t calc_num_meshes();
static int mesh_slot_offset(const int8_t slot);
static void store_mesh(const int8_t slot);
static void load_mesh(const int8_t slot, void * const into=NULL);
@@ -62,18 +79,20 @@ class MarlinSettings {
static void postprocess();
#if ENABLED(EEPROM_SETTINGS)
static bool eeprom_error;
static bool eeprom_error, validating;
#if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system
// That can store is enabled
static int16_t meshes_begin;
const static int16_t 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
static constexpr uint16_t 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
static bool _load();
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);
static void read_data(int &pos, uint8_t *value, uint16_t size, uint16_t *crc, const bool force=false);
static bool size_error(const uint16_t size);
#endif
};

View File

@@ -30,11 +30,13 @@
* http://arduino.cc/forum/index.php/topic,51842.0.html
*/
#include "dac_mcp4728.h"
#include "enum.h"
#include "MarlinConfig.h"
#if ENABLED(DAC_STEPPER_CURRENT)
#include "dac_mcp4728.h"
#include "enum.h"
uint16_t mcp4728_values[XYZE];
/**

77
Marlin/delay.h Normal file
View File

@@ -0,0 +1,77 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* AVR busy wait delay Cycles routines:
*
* DELAY_CYCLES(count): Delay execution in cycles
* DELAY_NS(count): Delay execution in nanoseconds
* DELAY_US(count): Delay execution in microseconds
*/
#ifndef MARLIN_DELAY_H
#define MARLIN_DELAY_H
#define nop() __asm__ __volatile__("nop;\n\t":::)
FORCE_INLINE static void __delay_4cycles(uint8_t cy) {
__asm__ __volatile__(
L("1")
A("dec %[cnt]")
A("nop")
A("brne 1b")
: [cnt] "+r"(cy) // output: +r means input+output
: // input:
: "cc" // clobbers:
);
}
/* ---------------- Delay in cycles */
FORCE_INLINE static void DELAY_CYCLES(uint16_t x) {
if (__builtin_constant_p(x)) {
#define MAXNOPS 4
if (x <= (MAXNOPS)) {
switch (x) { case 4: nop(); case 3: nop(); case 2: nop(); case 1: nop(); }
}
else {
const uint32_t rem = (x) % (MAXNOPS);
switch (rem) { case 3: nop(); case 2: nop(); case 1: nop(); }
if ((x = (x) / (MAXNOPS)))
__delay_4cycles(x); // if need more then 4 nop loop is more optimal
}
#undef MAXNOPS
}
else
__delay_4cycles(x / 4);
}
#undef nop
/* ---------------- Delay in nanoseconds */
#define DELAY_NS(x) DELAY_CYCLES( (x) * (F_CPU/1000000L) / 1000L )
/* ---------------- Delay in microseconds */
#define DELAY_US(x) DELAY_CYCLES( (x) * (F_CPU/1000000L) )
#endif // MARLIN_DELAY_H

View File

@@ -89,7 +89,7 @@ static void i2c_send(const uint8_t channel, const byte v) {
// This is for the MCP4018 I2C based digipot
void digipot_i2c_set_current(uint8_t channel, float current) {
i2c_send(channel, current_to_wiper(min(max(current, 0.0f), float(DIGIPOT_A4988_MAX_CURRENT))));
i2c_send(channel, current_to_wiper(MIN(MAX(current, 0), float(DIGIPOT_A4988_MAX_CURRENT))));
}
void digipot_i2c_init() {

View File

@@ -50,7 +50,7 @@ static void i2c_send(const byte addr, const byte a, const byte b) {
// This is for the MCP4451 I2C based digipot
void digipot_i2c_set_current(uint8_t channel, float current) {
current = min((float) max(current, 0.0f), DIGIPOT_I2C_MAX_CURRENT);
current = MIN((float) MAX(current, 0), DIGIPOT_I2C_MAX_CURRENT);
// these addresses are specific to Azteeg X3 Pro, can be set to others,
// In this case first digipot is at address A0=0, A1= 0, second one is at A0=0, A1= 1
byte addr = 0x2C; // channel 0-3

File diff suppressed because it is too large Load Diff

73
Marlin/drivers.h Normal file
View File

@@ -0,0 +1,73 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
#ifndef _DRIVERS_H_
#define _DRIVERS_H_
#include "MarlinConfig.h"
#define A4988 0x001
#define DRV8825 0x002
#define LV8729 0x003
#define L6470 0x104
#define TB6560 0x005
#define TB6600 0x006
#define TMC2100 0x007
#define TMC2130 0x108
#define TMC2130_STANDALONE 0x008
#define TMC2208 0x109
#define TMC2208_STANDALONE 0x009
#define TMC26X 0x10A
#define TMC26X_STANDALONE 0x00A
#define TMC2660 0x10B
#define TMC2660_STANDALONE 0x00B
#define _AXIS_DRIVER_TYPE(A,T) ( defined(A##_DRIVER_TYPE) && (A##_DRIVER_TYPE == T) )
#define AXIS_DRIVER_TYPE_X(T) _AXIS_DRIVER_TYPE(X,T)
#define AXIS_DRIVER_TYPE_Y(T) _AXIS_DRIVER_TYPE(Y,T)
#define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T)
#define AXIS_DRIVER_TYPE_X2(T) (ENABLED(X_DUAL_STEPPER_DRIVERS) || ENABLED(DUAL_X_CARRIAGE)) && _AXIS_DRIVER_TYPE(X2,T)
#define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
#define AXIS_DRIVER_TYPE_Z2(T) (ENABLED(Z_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Z2,T))
#define AXIS_DRIVER_TYPE_E0(T) (E_STEPPERS > 0 && _AXIS_DRIVER_TYPE(E0,T))
#define AXIS_DRIVER_TYPE_E1(T) (E_STEPPERS > 1 && _AXIS_DRIVER_TYPE(E1,T))
#define AXIS_DRIVER_TYPE_E2(T) (E_STEPPERS > 2 && _AXIS_DRIVER_TYPE(E2,T))
#define AXIS_DRIVER_TYPE_E3(T) (E_STEPPERS > 3 && _AXIS_DRIVER_TYPE(E3,T))
#define AXIS_DRIVER_TYPE_E4(T) (E_STEPPERS > 4 && _AXIS_DRIVER_TYPE(E4,T))
#define AXIS_DRIVER_TYPE(A,T) AXIS_DRIVER_TYPE_##A(T)
#define HAS_DRIVER(T) (AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) || \
AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) || \
AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || \
AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) || \
AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) || \
AXIS_DRIVER_TYPE_E4(T) )
// Test for supported TMC drivers that require advanced configuration
// Does not match standalone configurations
#define HAS_TRINAMIC (HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC2208))
#define AXIS_IS_TMC(A) ( AXIS_DRIVER_TYPE_##A(TMC2130) || \
AXIS_DRIVER_TYPE_##A(TMC2208) )
#endif // _DRIVERS_H_

View File

@@ -23,6 +23,9 @@
#ifndef __DURATION_T__
#define __DURATION_T__
#include <stdio.h>
#include <inttypes.h>
struct duration_t {
/**
* @brief Duration is stored in seconds
@@ -151,10 +154,10 @@ struct duration_t {
if (with_days) {
uint16_t d = this->day();
sprintf_P(buffer, PSTR("%ud %02u:%02u"), d, h % 24, m);
return d >= 10 ? 8 : 7;
return d >= 10 ? 9 : 8;
}
else if (h < 100) {
sprintf_P(buffer, PSTR("%02u:%02u"), h % 24, m);
sprintf_P(buffer, PSTR("%02u:%02u"), h, m);
return 5;
}
else {

View File

@@ -0,0 +1,40 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* emergency_parser.cpp - Intercept special commands directly in the serial stream
*/
#include "MarlinConfig.h"
#if ENABLED(EMERGENCY_PARSER)
#include "emergency_parser.h"
// Static data members
bool EmergencyParser::killed_by_M112; // = false
EmergencyParser::State EmergencyParser::state; // = EP_RESET
// Global instance
EmergencyParser emergency_parser;
#endif // EMERGENCY_PARSER

144
Marlin/emergency_parser.h Normal file
View File

@@ -0,0 +1,144 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* emergency_parser.h - Intercept special commands directly in the serial stream
*/
#ifndef _EMERGENCY_PARSER_H_
#define _EMERGENCY_PARSER_H_
// External references
extern volatile bool wait_for_user, wait_for_heatup;
void quickstop_stepper();
class EmergencyParser {
public:
// Currently looking for: M108, M112, M410
enum State : char {
EP_RESET,
EP_N,
EP_M,
EP_M1,
EP_M10,
EP_M108,
EP_M11,
EP_M112,
EP_M4,
EP_M41,
EP_M410,
EP_IGNORE // to '\n'
};
static bool killed_by_M112;
static State state;
EmergencyParser() {}
__attribute__((always_inline)) inline
static void update(const uint8_t c) {
switch (state) {
case EP_RESET:
switch (c) {
case ' ': break;
case 'N': state = EP_N; break;
case 'M': state = EP_M; break;
default: state = EP_IGNORE;
}
break;
case EP_N:
switch (c) {
case '0': case '1': case '2':
case '3': case '4': case '5':
case '6': case '7': case '8':
case '9': case '-': case ' ': break;
case 'M': state = EP_M; break;
default: state = EP_IGNORE;
}
break;
case EP_M:
switch (c) {
case ' ': break;
case '1': state = EP_M1; break;
case '4': state = EP_M4; break;
default: state = EP_IGNORE;
}
break;
case EP_M1:
switch (c) {
case '0': state = EP_M10; break;
case '1': state = EP_M11; break;
default: state = EP_IGNORE;
}
break;
case EP_M10:
state = (c == '8') ? EP_M108 : EP_IGNORE;
break;
case EP_M11:
state = (c == '2') ? EP_M112 : EP_IGNORE;
break;
case EP_M4:
state = (c == '1') ? EP_M41 : EP_IGNORE;
break;
case EP_M41:
state = (c == '0') ? EP_M410 : EP_IGNORE;
break;
case EP_IGNORE:
if (c == '\n') state = EP_RESET;
break;
default:
if (c == '\n') {
switch (state) {
case EP_M108:
wait_for_user = wait_for_heatup = false;
break;
case EP_M112:
killed_by_M112 = true;
break;
case EP_M410:
quickstop_stepper();
break;
default:
break;
}
state = EP_RESET;
}
}
}
};
extern EmergencyParser emergency_parser;
#endif // _EMERGENCY_PARSER_H_

View File

@@ -24,7 +24,7 @@
* Endstop Interrupts
*
* Without endstop interrupts the endstop pins must be polled continually in
* the stepper-ISR via endstops.update(), most of the time finding no change.
* the temperature-ISR via endstops.update(), most of the time finding no change.
* With this feature endstops.update() is called only when we know that at
* least one endstop has changed state, saving valuable CPU cycles.
*
@@ -40,6 +40,9 @@
#include "macros.h"
// One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstops.update(); }
/**
* Patch for pins_arduino.h (...\Arduino\hardware\arduino\avr\variants\mega\pins_arduino.h)
*
@@ -72,40 +75,30 @@
0 )
#endif
volatile uint8_t e_hit = 0; // Different from 0 when the endstops should be tested in detail.
// Must be reset to 0 by the test function when finished.
// Install Pin change interrupt for a pin. Can be called multiple times.
void pciSetup(byte pin) {
void pciSetup(const int8_t pin) {
SBI(*digitalPinToPCMSK(pin), digitalPinToPCMSKbit(pin)); // enable pin
SBI(PCIFR, digitalPinToPCICRbit(pin)); // clear any outstanding interrupt
SBI(PCICR, digitalPinToPCICRbit(pin)); // enable interrupt for the group
}
// This is what is really done inside the interrupts.
FORCE_INLINE void endstop_ISR_worker( void ) {
e_hit = 2; // Because the detection of a e-stop hit has a 1 step debouncer it has to be called at least twice.
}
// Use one Routine to handle each group
// One ISR for all EXT-Interrupts
void endstop_ISR(void) { endstop_ISR_worker(); }
// Handlers for pin change interrupts
#ifdef PCINT0_vect
ISR(PCINT0_vect) { endstop_ISR_worker(); }
ISR(PCINT0_vect) { endstop_ISR(); }
#endif
#ifdef PCINT1_vect
ISR(PCINT1_vect) { endstop_ISR_worker(); }
ISR(PCINT1_vect) { endstop_ISR(); }
#endif
#ifdef PCINT2_vect
ISR(PCINT2_vect) { endstop_ISR_worker(); }
ISR(PCINT2_vect) { endstop_ISR(); }
#endif
#ifdef PCINT3_vect
ISR(PCINT3_vect) { endstop_ISR_worker(); }
ISR(PCINT3_vect) { endstop_ISR(); }
#endif
void setup_endstop_interrupts( void ) {

View File

@@ -31,28 +31,39 @@
#include "stepper.h"
#include "ultralcd.h"
// TEST_ENDSTOP: test the old and the current status of an endstop
#define TEST_ENDSTOP(ENDSTOP) (TEST(current_endstop_bits & old_endstop_bits, ENDSTOP))
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
#include "endstop_interrupts.h"
#endif
Endstops endstops;
// public:
bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load()
volatile char Endstops::endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
volatile uint8_t Endstops::hit_state;
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
uint16_t
#else
byte
Endstops::esbits_t Endstops::live_state = 0;
#if ENABLED(ENDSTOP_NOISE_FILTER)
Endstops::esbits_t Endstops::validated_live_state;
uint8_t Endstops::endstop_poll_count;
#endif
Endstops::current_endstop_bits = 0,
Endstops::old_endstop_bits = 0;
#if HAS_BED_PROBE
volatile bool Endstops::z_probe_enabled = false;
#endif
// Initialized by settings.load()
#if ENABLED(X_DUAL_ENDSTOPS)
float Endstops::x_endstop_adj;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
float Endstops::y_endstop_adj;
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
float Endstops::z_endstop_adj;
#endif
/**
* Class and Instance Methods
*/
@@ -163,10 +174,93 @@ void Endstops::init() {
#endif
#endif
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
setup_endstop_interrupts();
#endif
// Enable endstops
enable_globally(
#if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
true
#else
false
#endif
);
} // Endstops::init
void Endstops::report_state() {
if (endstop_hit_bits) {
// Called at ~1KHz from Temperature ISR: Poll endstop state if required
void Endstops::poll() {
#if ENABLED(PINS_DEBUGGING)
run_monitor(); // report changes in endstop status
#endif
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) && ENABLED(ENDSTOP_NOISE_FILTER)
if (endstop_poll_count) update();
#elif DISABLED(ENDSTOP_INTERRUPTS_FEATURE) || ENABLED(ENDSTOP_NOISE_FILTER)
update();
#endif
}
void Endstops::enable_globally(const bool onoff) {
enabled_globally = enabled = onoff;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
update();
#endif
}
// Enable / disable endstop checking
void Endstops::enable(const bool onoff) {
enabled = onoff;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
update();
#endif
}
// Disable / Enable endstops based on ENSTOPS_ONLY_FOR_HOMING and global enable
void Endstops::not_homing() {
enabled = enabled_globally;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
update();
#endif
}
#if ENABLED(VALIDATE_HOMING_ENDSTOPS)
// If the last move failed to trigger an endstop, call kill
void Endstops::validate_homing_move() {
if (trigger_state()) hit_on_purpose();
else kill(PSTR(MSG_ERR_HOMING_FAILED));
}
#endif
// Enable / disable endstop z-probe checking
#if HAS_BED_PROBE
void Endstops::enable_z_probe(const bool onoff) {
z_probe_enabled = onoff;
#if ENABLED(ENDSTOP_INTERRUPTS_FEATURE)
update();
#endif
}
#endif
#if ENABLED(PINS_DEBUGGING)
void Endstops::run_monitor() {
if (!monitor_flag) return;
static uint8_t monitor_count = 16; // offset this check from the others
monitor_count += _BV(1); // 15 Hz
monitor_count &= 0x7F;
if (!monitor_count) monitor(); // report changes in endstop status
}
#endif
void Endstops::event_handler() {
static uint8_t prev_hit_state; // = 0
if (hit_state && hit_state != prev_hit_state) {
#if ENABLED(ULTRA_LCD)
char chrX = ' ', chrY = ' ', chrZ = ' ', chrP = ' ';
#define _SET_STOP_CHAR(A,C) (chr## A = C)
@@ -175,11 +269,11 @@ void Endstops::report_state() {
#endif
#define _ENDSTOP_HIT_ECHO(A,C) do{ \
SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", stepper.triggered_position_mm(A ##_AXIS)); \
SERIAL_ECHOPAIR(" " STRINGIFY(A) ":", planner.triggered_position_mm(_AXIS(A))); \
_SET_STOP_CHAR(A,C); }while(0)
#define _ENDSTOP_HIT_TEST(A,C) \
if (TEST(endstop_hit_bits, A ##_MIN) || TEST(endstop_hit_bits, A ##_MAX)) \
if (TEST(hit_state, A ##_MIN) || TEST(hit_state, A ##_MAX)) \
_ENDSTOP_HIT_ECHO(A,C)
#define ENDSTOP_HIT_TEST_X() _ENDSTOP_HIT_TEST(X,'X')
@@ -194,7 +288,7 @@ void Endstops::report_state() {
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
#define P_AXIS Z_AXIS
if (TEST(endstop_hit_bits, Z_MIN_PROBE)) _ENDSTOP_HIT_ECHO(P, 'P');
if (TEST(hit_state, Z_MIN_PROBE)) _ENDSTOP_HIT_ECHO(P, 'P');
#endif
SERIAL_EOL();
@@ -202,10 +296,8 @@ void Endstops::report_state() {
lcd_status_printf_P(0, PSTR(MSG_LCD_ENDSTOPS " %c %c %c %c"), chrX, chrY, chrZ, chrP);
#endif
hit_on_purpose();
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) && ENABLED(SDSUPPORT)
if (stepper.abort_on_endstop_hit) {
if (planner.abort_on_endstop_hit) {
card.sdprinting = false;
card.closefile();
quickstop_stepper();
@@ -213,14 +305,19 @@ void Endstops::report_state() {
}
#endif
}
prev_hit_state = hit_state;
} // Endstops::report_state
void Endstops::M119() {
static void print_es_state(const bool is_hit, const char * const label=NULL) {
if (label) serialprintPGM(label);
SERIAL_PROTOCOLPGM(": ");
serialprintPGM(is_hit ? PSTR(MSG_ENDSTOP_HIT) : PSTR(MSG_ENDSTOP_OPEN));
SERIAL_EOL();
}
void _O2 Endstops::M119() {
SERIAL_PROTOCOLLNPGM(MSG_M119_REPORT);
#define ES_REPORT(AXIS) do{ \
SERIAL_PROTOCOLPGM(MSG_##AXIS); \
SERIAL_PROTOCOLLN(((READ(AXIS##_PIN)^AXIS##_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN)); \
}while(0)
#define ES_REPORT(S) print_es_state(READ(S##_PIN) != S##_ENDSTOP_INVERTING, PSTR(MSG_##S))
#if HAS_X_MIN
ES_REPORT(X_MIN);
#endif
@@ -258,152 +355,61 @@ void Endstops::M119() {
ES_REPORT(Z2_MAX);
#endif
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
SERIAL_PROTOCOLLN(((READ(Z_MIN_PROBE_PIN)^Z_MIN_PROBE_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
print_es_state(READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING, PSTR(MSG_Z_PROBE));
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
SERIAL_PROTOCOLPGM(MSG_FILAMENT_RUNOUT_SENSOR);
SERIAL_PROTOCOLLN(((READ(FIL_RUNOUT_PIN)^FIL_RUNOUT_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
#if NUM_RUNOUT_SENSORS == 1
print_es_state(READ(FIL_RUNOUT_PIN) != FIL_RUNOUT_INVERTING, PSTR(MSG_FILAMENT_RUNOUT_SENSOR));
#else
for (uint8_t i = 1; i <= NUM_RUNOUT_SENSORS; i++) {
pin_t pin;
switch (i) {
default: continue;
case 1: pin = FIL_RUNOUT_PIN; break;
case 2: pin = FIL_RUNOUT2_PIN; break;
#if NUM_RUNOUT_SENSORS > 2
case 3: pin = FIL_RUNOUT3_PIN; break;
#if NUM_RUNOUT_SENSORS > 3
case 4: pin = FIL_RUNOUT4_PIN; break;
#if NUM_RUNOUT_SENSORS > 4
case 5: pin = FIL_RUNOUT5_PIN; break;
#endif
#endif
#endif
}
SERIAL_PROTOCOLPGM(MSG_FILAMENT_RUNOUT_SENSOR);
if (i > 1) { SERIAL_CHAR(' '); SERIAL_CHAR('0' + i); }
print_es_state(digitalRead(pin) != FIL_RUNOUT_INVERTING);
}
#endif
#endif
} // Endstops::M119
#if ENABLED(X_DUAL_ENDSTOPS)
void Endstops::test_dual_x_endstops(const EndstopEnum es1, const EndstopEnum es2) {
byte x_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for X, bit 1 for X2
if (x_test && stepper.current_block->steps[X_AXIS] > 0) {
SBI(endstop_hit_bits, X_MIN);
if (!stepper.performing_homing || (x_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
stepper.kill_current_block();
}
}
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
void Endstops::test_dual_y_endstops(const EndstopEnum es1, const EndstopEnum es2) {
byte y_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Y, bit 1 for Y2
if (y_test && stepper.current_block->steps[Y_AXIS] > 0) {
SBI(endstop_hit_bits, Y_MIN);
if (!stepper.performing_homing || (y_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
stepper.kill_current_block();
}
}
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
void Endstops::test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2) {
byte z_test = TEST_ENDSTOP(es1) | (TEST_ENDSTOP(es2) << 1); // bit 0 for Z, bit 1 for Z2
if (z_test && stepper.current_block->steps[Z_AXIS] > 0) {
SBI(endstop_hit_bits, Z_MIN);
if (!stepper.performing_homing || (z_test == 0x3)) //if not performing home or if both endstops were trigged during homing...
stepper.kill_current_block();
}
}
#endif
// The following routines are called from an ISR context. It could be the temperature ISR, the
// endstop ISR or the Stepper ISR.
// Check endstops - Called from ISR!
#define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX
#define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN
#define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING
// Check endstops - Could be called from Temperature ISR!
void Endstops::update() {
#define _ENDSTOP(AXIS, MINMAX) AXIS ##_## MINMAX
#define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN
#define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING
#define _ENDSTOP_HIT(AXIS, MINMAX) SBI(endstop_hit_bits, _ENDSTOP(AXIS, MINMAX))
#if DISABLED(ENDSTOP_NOISE_FILTER)
if (!abort_enabled()) return;
#endif
// UPDATE_ENDSTOP_BIT: set the current endstop bits for an endstop to its status
#define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT(current_endstop_bits, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX)))
// COPY_BIT: copy the value of SRC_BIT to DST_BIT in DST
#define COPY_BIT(DST, SRC_BIT, DST_BIT) SET_BIT(DST, DST_BIT, TEST(DST, SRC_BIT))
#define UPDATE_ENDSTOP(AXIS,MINMAX) do { \
UPDATE_ENDSTOP_BIT(AXIS, MINMAX); \
if (TEST_ENDSTOP(_ENDSTOP(AXIS, MINMAX)) && stepper.current_block->steps[_AXIS(AXIS)] > 0) { \
_ENDSTOP_HIT(AXIS, MINMAX); \
stepper.endstop_triggered(_AXIS(AXIS)); \
} \
}while(0)
#define UPDATE_ENDSTOP_BIT(AXIS, MINMAX) SET_BIT_TO(live_state, _ENDSTOP(AXIS, MINMAX), (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX)))
#define COPY_LIVE_STATE(SRC_BIT, DST_BIT) SET_BIT_TO(live_state, DST_BIT, TEST(live_state, SRC_BIT))
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ)
// If G38 command is active check Z_MIN_PROBE for ALL movement
if (G38_move) {
UPDATE_ENDSTOP_BIT(Z, MIN_PROBE);
if (TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE))) {
if (stepper.current_block->steps[_AXIS(X)] > 0) { _ENDSTOP_HIT(X, MIN); stepper.endstop_triggered(_AXIS(X)); }
else if (stepper.current_block->steps[_AXIS(Y)] > 0) { _ENDSTOP_HIT(Y, MIN); stepper.endstop_triggered(_AXIS(Y)); }
else if (stepper.current_block->steps[_AXIS(Z)] > 0) { _ENDSTOP_HIT(Z, MIN); stepper.endstop_triggered(_AXIS(Z)); }
G38_endstop_hit = true;
}
}
#endif
/**
* Define conditions for checking endstops
*/
#if IS_CORE
#define S_(N) stepper.current_block->steps[CORE_AXIS_##N]
#define D_(N) stepper.motor_direction(CORE_AXIS_##N)
#endif
#if CORE_IS_XY || CORE_IS_XZ
/**
* Head direction in -X axis for CoreXY and CoreXZ bots.
*
* If steps differ, both axes are moving.
* If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z, handled below)
* If DeltaA == DeltaB, the movement is only in the 1st axis (X)
*/
#if ENABLED(COREXY) || ENABLED(COREXZ)
#define X_CMP ==
#else
#define X_CMP !=
#endif
#define X_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) X_CMP D_(2)) )
#define X_AXIS_HEAD X_HEAD
#else
#define X_MOVE_TEST stepper.current_block->steps[X_AXIS] > 0
#define X_AXIS_HEAD X_AXIS
#endif
#if CORE_IS_XY || CORE_IS_YZ
/**
* Head direction in -Y axis for CoreXY / CoreYZ bots.
*
* If steps differ, both axes are moving
* If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y)
* If DeltaA == -DeltaB, the movement is only in the 2nd axis (Y or Z)
*/
#if ENABLED(COREYX) || ENABLED(COREYZ)
#define Y_CMP ==
#else
#define Y_CMP !=
#endif
#define Y_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Y_CMP D_(2)) )
#define Y_AXIS_HEAD Y_HEAD
#else
#define Y_MOVE_TEST stepper.current_block->steps[Y_AXIS] > 0
#define Y_AXIS_HEAD Y_AXIS
#endif
#if CORE_IS_XZ || CORE_IS_YZ
/**
* Head direction in -Z axis for CoreXZ or CoreYZ bots.
*
* If steps differ, both axes are moving
* If DeltaA == DeltaB, the movement is only in the 1st axis (X or Y, already handled above)
* If DeltaA == -DeltaB, the movement is only in the 2nd axis (Z)
*/
#if ENABLED(COREZX) || ENABLED(COREZY)
#define Z_CMP ==
#else
#define Z_CMP !=
#endif
#define Z_MOVE_TEST ( S_(1) != S_(2) || (S_(1) > 0 && D_(1) Z_CMP D_(2)) )
#define Z_AXIS_HEAD Z_HEAD
#else
#define Z_MOVE_TEST stepper.current_block->steps[Z_AXIS] > 0
#define Z_AXIS_HEAD Z_AXIS
if (G38_move) UPDATE_ENDSTOP_BIT(Z, MIN_PROBE);
#endif
// With Dual X, endstops are only checked in the homing direction for the active extruder
#if ENABLED(DUAL_X_CARRIAGE)
#define E0_ACTIVE stepper.current_block->active_extruder == 0
#define E0_ACTIVE stepper.movement_extruder() == 0
#define X_MIN_TEST ((X_HOME_DIR < 0 && E0_ACTIVE) || (X2_HOME_DIR < 0 && !E0_ACTIVE))
#define X_MAX_TEST ((X_HOME_DIR > 0 && E0_ACTIVE) || (X2_HOME_DIR > 0 && !E0_ACTIVE))
#else
@@ -411,124 +417,358 @@ void Endstops::update() {
#define X_MAX_TEST true
#endif
// Use HEAD for core axes, AXIS for others
#if CORE_IS_XY || CORE_IS_XZ
#define X_AXIS_HEAD X_HEAD
#else
#define X_AXIS_HEAD X_AXIS
#endif
#if CORE_IS_XY || CORE_IS_YZ
#define Y_AXIS_HEAD Y_HEAD
#else
#define Y_AXIS_HEAD Y_AXIS
#endif
#if CORE_IS_XZ || CORE_IS_YZ
#define Z_AXIS_HEAD Z_HEAD
#else
#define Z_AXIS_HEAD Z_AXIS
#endif
/**
* Check and update endstops according to conditions
* Check and update endstops
*/
if (X_MOVE_TEST) {
#if HAS_X_MIN
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MIN);
#if HAS_X2_MIN
UPDATE_ENDSTOP_BIT(X2, MIN);
#else
COPY_LIVE_STATE(X_MIN, X2_MIN);
#endif
#else
UPDATE_ENDSTOP_BIT(X, MIN);
#endif
#endif
#if HAS_X_MAX
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MAX);
#if HAS_X2_MAX
UPDATE_ENDSTOP_BIT(X2, MAX);
#else
COPY_LIVE_STATE(X_MAX, X2_MAX);
#endif
#else
UPDATE_ENDSTOP_BIT(X, MAX);
#endif
#endif
#if HAS_Y_MIN
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MIN);
#if HAS_Y2_MIN
UPDATE_ENDSTOP_BIT(Y2, MIN);
#else
COPY_LIVE_STATE(Y_MIN, Y2_MIN);
#endif
#else
UPDATE_ENDSTOP_BIT(Y, MIN);
#endif
#endif
#if HAS_Y_MAX
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MAX);
#if HAS_Y2_MAX
UPDATE_ENDSTOP_BIT(Y2, MAX);
#else
COPY_LIVE_STATE(Y_MAX, Y2_MAX);
#endif
#else
UPDATE_ENDSTOP_BIT(Y, MAX);
#endif
#endif
#if HAS_Z_MIN
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MIN);
#if HAS_Z2_MIN
UPDATE_ENDSTOP_BIT(Z2, MIN);
#else
COPY_LIVE_STATE(Z_MIN, Z2_MIN);
#endif
#elif ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
UPDATE_ENDSTOP_BIT(Z, MIN);
#elif Z_HOME_DIR < 0
UPDATE_ENDSTOP_BIT(Z, MIN);
#endif
#endif
// When closing the gap check the enabled probe
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
UPDATE_ENDSTOP_BIT(Z, MIN_PROBE);
#endif
#if HAS_Z_MAX
// Check both Z dual endstops
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MAX);
#if HAS_Z2_MAX
UPDATE_ENDSTOP_BIT(Z2, MAX);
#else
COPY_LIVE_STATE(Z_MAX, Z2_MAX);
#endif
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
// If this pin isn't the bed probe it's the Z endstop
UPDATE_ENDSTOP_BIT(Z, MAX);
#endif
#endif
#if ENABLED(ENDSTOP_NOISE_FILTER)
/**
* Filtering out noise on endstops requires a delayed decision. Let's assume, due to noise,
* that 50% of endstop signal samples are good and 50% are bad (assuming normal distribution
* of random noise). Then the first sample has a 50% chance to be good or bad. The 2nd sample
* also has a 50% chance to be good or bad. The chances of 2 samples both being bad becomes
* 50% of 50%, or 25%. That was the previous implementation of Marlin endstop handling. It
* reduces chances of bad readings in half, at the cost of 1 extra sample period, but chances
* still exist. The only way to reduce them further is to increase the number of samples.
* To reduce the chance to 1% (1/128th) requires 7 samples (adding 7ms of delay).
*/
static esbits_t old_live_state;
if (old_live_state != live_state) {
endstop_poll_count = 7;
old_live_state = live_state;
}
else if (endstop_poll_count && !--endstop_poll_count)
validated_live_state = live_state;
if (!abort_enabled()) return;
#endif
// Test the current status of an endstop
#define TEST_ENDSTOP(ENDSTOP) (TEST(state(), ENDSTOP))
// Record endstop was hit
#define _ENDSTOP_HIT(AXIS, MINMAX) SBI(hit_state, _ENDSTOP(AXIS, MINMAX))
// Call the endstop triggered routine for single endstops
#define PROCESS_ENDSTOP(AXIS,MINMAX) do { \
if (TEST_ENDSTOP(_ENDSTOP(AXIS, MINMAX))) { \
_ENDSTOP_HIT(AXIS, MINMAX); \
planner.endstop_triggered(_AXIS(AXIS)); \
} \
}while(0)
// Call the endstop triggered routine for dual endstops
#define PROCESS_DUAL_ENDSTOP(AXIS1, AXIS2, MINMAX) do { \
const byte dual_hit = TEST_ENDSTOP(_ENDSTOP(AXIS1, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(AXIS2, MINMAX)) << 1); \
if (dual_hit) { \
_ENDSTOP_HIT(AXIS1, MINMAX); \
/* if not performing home or if both endstops were trigged during homing... */ \
if (!stepper.homing_dual_axis || dual_hit == 0b11) \
planner.endstop_triggered(_AXIS(AXIS1)); \
} \
}while(0)
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ)
// If G38 command is active check Z_MIN_PROBE for ALL movement
if (G38_move) {
if (TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE))) {
if (stepper.axis_is_moving(X_AXIS)) { _ENDSTOP_HIT(X, MIN); planner.endstop_triggered(X_AXIS); }
else if (stepper.axis_is_moving(Y_AXIS)) { _ENDSTOP_HIT(Y, MIN); planner.endstop_triggered(Y_AXIS); }
else if (stepper.axis_is_moving(Z_AXIS)) { _ENDSTOP_HIT(Z, MIN); planner.endstop_triggered(Z_AXIS); }
G38_endstop_hit = true;
}
}
#endif
// Now, we must signal, after validation, if an endstop limit is pressed or not
if (stepper.axis_is_moving(X_AXIS)) {
if (stepper.motor_direction(X_AXIS_HEAD)) { // -direction
#if HAS_X_MIN
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MIN);
#if HAS_X2_MIN
UPDATE_ENDSTOP_BIT(X2, MIN);
#else
COPY_BIT(current_endstop_bits, X_MIN, X2_MIN);
#endif
test_dual_x_endstops(X_MIN, X2_MIN);
PROCESS_DUAL_ENDSTOP(X, X2, MIN);
#else
if (X_MIN_TEST) UPDATE_ENDSTOP(X, MIN);
if (X_MIN_TEST) PROCESS_ENDSTOP(X, MIN);
#endif
#endif
}
else { // +direction
#if HAS_X_MAX
#if ENABLED(X_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(X, MAX);
#if HAS_X2_MAX
UPDATE_ENDSTOP_BIT(X2, MAX);
#else
COPY_BIT(current_endstop_bits, X_MAX, X2_MAX);
#endif
test_dual_x_endstops(X_MAX, X2_MAX);
PROCESS_DUAL_ENDSTOP(X, X2, MAX);
#else
if (X_MIN_TEST) UPDATE_ENDSTOP(X, MAX);
if (X_MAX_TEST) PROCESS_ENDSTOP(X, MAX);
#endif
#endif
}
}
if (Y_MOVE_TEST) {
if (stepper.axis_is_moving(Y_AXIS)) {
if (stepper.motor_direction(Y_AXIS_HEAD)) { // -direction
#if HAS_Y_MIN
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MIN);
#if HAS_Y2_MIN
UPDATE_ENDSTOP_BIT(Y2, MIN);
#else
COPY_BIT(current_endstop_bits, Y_MIN, Y2_MIN);
#endif
test_dual_y_endstops(Y_MIN, Y2_MIN);
PROCESS_DUAL_ENDSTOP(Y, Y2, MIN);
#else
UPDATE_ENDSTOP(Y, MIN);
PROCESS_ENDSTOP(Y, MIN);
#endif
#endif
}
else { // +direction
#if HAS_Y_MAX
#if ENABLED(Y_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Y, MAX);
#if HAS_Y2_MAX
UPDATE_ENDSTOP_BIT(Y2, MAX);
#else
COPY_BIT(current_endstop_bits, Y_MAX, Y2_MAX);
#endif
test_dual_y_endstops(Y_MAX, Y2_MAX);
PROCESS_DUAL_ENDSTOP(Y, Y2, MAX);
#else
UPDATE_ENDSTOP(Y, MAX);
PROCESS_ENDSTOP(Y, MAX);
#endif
#endif
}
}
if (Z_MOVE_TEST) {
if (stepper.axis_is_moving(Z_AXIS)) {
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
#if HAS_Z_MIN
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MIN);
#if HAS_Z2_MIN
UPDATE_ENDSTOP_BIT(Z2, MIN);
#else
COPY_BIT(current_endstop_bits, Z_MIN, Z2_MIN);
#endif
test_dual_z_endstops(Z_MIN, Z2_MIN);
PROCESS_DUAL_ENDSTOP(Z, Z2, MIN);
#else
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
if (z_probe_enabled) UPDATE_ENDSTOP(Z, MIN);
if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN);
#elif ENABLED(Z_MIN_PROBE_ENDSTOP)
if (!z_probe_enabled) PROCESS_ENDSTOP(Z, MIN);
#else
UPDATE_ENDSTOP(Z, MIN);
PROCESS_ENDSTOP(Z, MIN);
#endif
#endif
#endif
// When closing the gap check the enabled probe
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
if (z_probe_enabled) {
UPDATE_ENDSTOP(Z, MIN_PROBE);
if (TEST_ENDSTOP(Z_MIN_PROBE)) SBI(endstop_hit_bits, Z_MIN_PROBE);
}
if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN_PROBE);
#endif
}
else { // Z +direction. Gantry up, bed down.
#if HAS_Z_MAX
// Check both Z dual endstops
#if ENABLED(Z_DUAL_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MAX);
#if HAS_Z2_MAX
UPDATE_ENDSTOP_BIT(Z2, MAX);
#else
COPY_BIT(current_endstop_bits, Z_MAX, Z2_MAX);
#endif
test_dual_z_endstops(Z_MAX, Z2_MAX);
// If this pin is not hijacked for the bed probe
// then it belongs to the Z endstop
PROCESS_DUAL_ENDSTOP(Z, Z2, MAX);
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
UPDATE_ENDSTOP(Z, MAX);
// If this pin is not hijacked for the bed probe
// then it belongs to the Z endstop
PROCESS_ENDSTOP(Z, MAX);
#endif
#endif
}
}
old_endstop_bits = current_endstop_bits;
} // Endstops::update()
#if ENABLED(PINS_DEBUGGING)
bool Endstops::monitor_flag = false;
/**
* monitors endstops & Z probe for changes
*
* If a change is detected then the LED is toggled and
* a message is sent out the serial port
*
* Yes, we could miss a rapid back & forth change but
* that won't matter because this is all manual.
*
*/
void Endstops::monitor() {
static uint16_t old_live_state_local = 0;
static uint8_t local_LED_status = 0;
uint16_t live_state_local = 0;
#if HAS_X_MIN
if (READ(X_MIN_PIN)) SBI(live_state_local, X_MIN);
#endif
#if HAS_X_MAX
if (READ(X_MAX_PIN)) SBI(live_state_local, X_MAX);
#endif
#if HAS_Y_MIN
if (READ(Y_MIN_PIN)) SBI(live_state_local, Y_MIN);
#endif
#if HAS_Y_MAX
if (READ(Y_MAX_PIN)) SBI(live_state_local, Y_MAX);
#endif
#if HAS_Z_MIN
if (READ(Z_MIN_PIN)) SBI(live_state_local, Z_MIN);
#endif
#if HAS_Z_MAX
if (READ(Z_MAX_PIN)) SBI(live_state_local, Z_MAX);
#endif
#if HAS_Z_MIN_PROBE_PIN
if (READ(Z_MIN_PROBE_PIN)) SBI(live_state_local, Z_MIN_PROBE);
#endif
#if HAS_X2_MIN
if (READ(X2_MIN_PIN)) SBI(live_state_local, X2_MIN);
#endif
#if HAS_X2_MAX
if (READ(X2_MAX_PIN)) SBI(live_state_local, X2_MAX);
#endif
#if HAS_Y2_MIN
if (READ(Y2_MIN_PIN)) SBI(live_state_local, Y2_MIN);
#endif
#if HAS_Y2_MAX
if (READ(Y2_MAX_PIN)) SBI(live_state_local, Y2_MAX);
#endif
#if HAS_Z2_MIN
if (READ(Z2_MIN_PIN)) SBI(live_state_local, Z2_MIN);
#endif
#if HAS_Z2_MAX
if (READ(Z2_MAX_PIN)) SBI(live_state_local, Z2_MAX);
#endif
uint16_t endstop_change = live_state_local ^ old_live_state_local;
if (endstop_change) {
#if HAS_X_MIN
if (TEST(endstop_change, X_MIN)) SERIAL_PROTOCOLPAIR(" X_MIN:", TEST(live_state_local, X_MIN));
#endif
#if HAS_X_MAX
if (TEST(endstop_change, X_MAX)) SERIAL_PROTOCOLPAIR(" X_MAX:", TEST(live_state_local, X_MAX));
#endif
#if HAS_Y_MIN
if (TEST(endstop_change, Y_MIN)) SERIAL_PROTOCOLPAIR(" Y_MIN:", TEST(live_state_local, Y_MIN));
#endif
#if HAS_Y_MAX
if (TEST(endstop_change, Y_MAX)) SERIAL_PROTOCOLPAIR(" Y_MAX:", TEST(live_state_local, Y_MAX));
#endif
#if HAS_Z_MIN
if (TEST(endstop_change, Z_MIN)) SERIAL_PROTOCOLPAIR(" Z_MIN:", TEST(live_state_local, Z_MIN));
#endif
#if HAS_Z_MAX
if (TEST(endstop_change, Z_MAX)) SERIAL_PROTOCOLPAIR(" Z_MAX:", TEST(live_state_local, Z_MAX));
#endif
#if HAS_Z_MIN_PROBE_PIN
if (TEST(endstop_change, Z_MIN_PROBE)) SERIAL_PROTOCOLPAIR(" PROBE:", TEST(live_state_local, Z_MIN_PROBE));
#endif
#if HAS_X2_MIN
if (TEST(endstop_change, X2_MIN)) SERIAL_PROTOCOLPAIR(" X2_MIN:", TEST(live_state_local, X2_MIN));
#endif
#if HAS_X2_MAX
if (TEST(endstop_change, X2_MAX)) SERIAL_PROTOCOLPAIR(" X2_MAX:", TEST(live_state_local, X2_MAX));
#endif
#if HAS_Y2_MIN
if (TEST(endstop_change, Y2_MIN)) SERIAL_PROTOCOLPAIR(" Y2_MIN:", TEST(live_state_local, Y2_MIN));
#endif
#if HAS_Y2_MAX
if (TEST(endstop_change, Y2_MAX)) SERIAL_PROTOCOLPAIR(" Y2_MAX:", TEST(live_state_local, Y2_MAX));
#endif
#if HAS_Z2_MIN
if (TEST(endstop_change, Z2_MIN)) SERIAL_PROTOCOLPAIR(" Z2_MIN:", TEST(live_state_local, Z2_MIN));
#endif
#if HAS_Z2_MAX
if (TEST(endstop_change, Z2_MAX)) SERIAL_PROTOCOLPAIR(" Z2_MAX:", TEST(live_state_local, Z2_MAX));
#endif
SERIAL_PROTOCOLPGM("\n\n");
analogWrite(LED_PIN, local_LED_status);
local_LED_status ^= 255;
old_live_state_local = live_state_local;
}
}
#endif // PINS_DEBUGGING

View File

@@ -21,53 +21,115 @@
*/
/**
* endstops.h - manages endstops
* endstops.h - manages endstops
*/
#ifndef ENDSTOPS_H
#define ENDSTOPS_H
#ifndef __ENDSTOPS_H__
#define __ENDSTOPS_H__
#include "enum.h"
#include "MarlinConfig.h"
#define VALIDATE_HOMING_ENDSTOPS
enum EndstopEnum : char {
X_MIN,
Y_MIN,
Z_MIN,
Z_MIN_PROBE,
X_MAX,
Y_MAX,
Z_MAX,
X2_MIN,
X2_MAX,
Y2_MIN,
Y2_MAX,
Z2_MIN,
Z2_MAX
};
class Endstops {
public:
static bool enabled, enabled_globally;
static volatile char endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
static uint16_t
typedef uint16_t esbits_t;
#if ENABLED(X_DUAL_ENDSTOPS)
static float x_endstop_adj;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
static float y_endstop_adj;
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
static float z_endstop_adj;
#endif
#else
static byte
typedef uint8_t esbits_t;
#endif
current_endstop_bits, old_endstop_bits;
Endstops() {
enable_globally(
#if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
true
#else
false
#endif
);
};
private:
static esbits_t live_state;
static volatile uint8_t hit_state; // Use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT index
#if ENABLED(ENDSTOP_NOISE_FILTER)
static esbits_t validated_live_state;
static uint8_t endstop_poll_count; // Countdown from threshold for polling
#endif
public:
Endstops() {};
/**
* Initialize the endstop pins
*/
void init();
static void init();
/**
* Update the endstops bits from the pins
* Are endstops or the probe set to abort the move?
*/
FORCE_INLINE static bool abort_enabled() {
return (enabled
#if HAS_BED_PROBE
|| z_probe_enabled
#endif
);
}
/**
* Periodic call to poll endstops if required. Called from temperature ISR
*/
static void poll();
/**
* Update endstops bits from the pins. Apply filtering to get a verified state.
* If abort_enabled() and moving towards a triggered switch, abort the current move.
* Called from ISR contexts.
*/
static void update();
/**
* Print an error message reporting the position when the endstops were last hit.
* Get Endstop hit state.
*/
static void report_state(); //call from somewhere to create an serial error message with the locations the endstops where hit, in case they were triggered
FORCE_INLINE static uint8_t trigger_state() { return hit_state; }
/**
* Get current endstops state
*/
FORCE_INLINE static esbits_t state() {
return
#if ENABLED(ENDSTOP_NOISE_FILTER)
validated_live_state
#else
live_state
#endif
;
}
/**
* Report endstop hits to serial. Called from loop().
*/
static void event_handler();
/**
* Report endstop positions in response to M119
@@ -75,43 +137,38 @@ class Endstops {
static void M119();
// Enable / disable endstop checking globally
static void enable_globally(bool onoff=true) { enabled_globally = enabled = onoff; }
static void enable_globally(const bool onoff=true);
// Enable / disable endstop checking
static void enable(bool onoff=true) { enabled = onoff; }
static void enable(const bool onoff=true);
// Disable / Enable endstops based on ENSTOPS_ONLY_FOR_HOMING and global enable
static void not_homing() { enabled = enabled_globally; }
static void not_homing();
#if ENABLED(VALIDATE_HOMING_ENDSTOPS)
// If the last move failed to trigger an endstop, call kill
static void validate_homing_move();
#else
FORCE_INLINE static void validate_homing_move() { hit_on_purpose(); }
#endif
// Clear endstops (i.e., they were hit intentionally) to suppress the report
static void hit_on_purpose() { endstop_hit_bits = 0; }
FORCE_INLINE static void hit_on_purpose() { hit_state = 0; }
// Enable / disable endstop z-probe checking
#if HAS_BED_PROBE
static volatile bool z_probe_enabled;
static void enable_z_probe(bool onoff=true) { z_probe_enabled = onoff; }
static void enable_z_probe(const bool onoff=true);
#endif
private:
#if ENABLED(X_DUAL_ENDSTOPS)
static void test_dual_x_endstops(const EndstopEnum es1, const EndstopEnum es2);
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
static void test_dual_y_endstops(const EndstopEnum es1, const EndstopEnum es2);
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
static void test_dual_z_endstops(const EndstopEnum es1, const EndstopEnum es2);
// Debugging of endstops
#if ENABLED(PINS_DEBUGGING)
static bool monitor_flag;
static void monitor();
static void run_monitor();
#endif
};
extern Endstops endstops;
#if HAS_BED_PROBE
#define ENDSTOPS_ENABLED (endstops.enabled || endstops.z_probe_enabled)
#else
#define ENDSTOPS_ENABLED endstops.enabled
#endif
#endif // ENDSTOPS_H
#endif // __ENDSTOPS_H__

View File

@@ -28,24 +28,27 @@
/**
* Axis indices as enumerated constants
*
* Special axis:
* - A_AXIS and B_AXIS are used by COREXY printers
* - X_HEAD and Y_HEAD is used for systems that don't have a 1:1 relationship
* between X_AXIS and X Head movement, like CoreXY bots
* - X_AXIS, Y_AXIS, and Z_AXIS should be used for axes in Cartesian space
* - A_AXIS, B_AXIS, and C_AXIS should be used for Steppers, corresponding to XYZ on Cartesians
* - X_HEAD, Y_HEAD, and Z_HEAD should be used for Steppers on Core kinematics
*/
enum AxisEnum {
NO_AXIS = -1,
enum AxisEnum : unsigned char {
X_AXIS = 0,
A_AXIS = 0,
Y_AXIS = 1,
B_AXIS = 1,
Z_AXIS = 2,
C_AXIS = 2,
E_AXIS = 3,
X_HEAD = 4,
Y_HEAD = 5,
Z_HEAD = 6,
ALL_AXES = 100
E_CART = 3,
#if ENABLED(HANGPRINTER) // Hangprinter order: A_AXIS, B_AXIS, C_AXIS, D_AXIS, E_AXIS
D_AXIS = 3,
E_AXIS = 4,
#else
E_AXIS = 3,
#endif
X_HEAD, Y_HEAD, Z_HEAD,
ALL_AXES = 0xFE,
NO_AXIS = 0xFF
};
#define LOOP_S_LE_N(VAR, S, N) for (uint8_t VAR=S; VAR<=N; VAR++)
@@ -55,8 +58,11 @@ enum AxisEnum {
#define LOOP_NA(VAR) LOOP_L_N(VAR, NUM_AXIS)
#define LOOP_XYZ(VAR) LOOP_S_LE_N(VAR, X_AXIS, Z_AXIS)
#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_AXIS)
#define LOOP_XYZE(VAR) LOOP_S_LE_N(VAR, X_AXIS, E_CART)
#define LOOP_XYZE_N(VAR) LOOP_S_L_N(VAR, X_AXIS, XYZE_N)
#define LOOP_MOV_AXIS(VAR) LOOP_S_L_N(VAR, A_AXIS, MOV_AXIS)
#define LOOP_NUM_AXIS(VAR) LOOP_S_L_N(VAR, A_AXIS, NUM_AXIS)
#define LOOP_NUM_AXIS_N(VAR) LOOP_S_L_N(VAR, A_AXIS, NUM_AXIS_N)
typedef enum {
LINEARUNIT_MM,
@@ -73,7 +79,7 @@ typedef enum {
* Debug flags
* Not yet widely applied
*/
enum DebugFlags {
enum DebugFlags : unsigned char {
DEBUG_NONE = 0,
DEBUG_ECHO = _BV(0), ///< Echo commands in order as they are processed
DEBUG_INFO = _BV(1), ///< Print messages for code that has debug output
@@ -85,53 +91,23 @@ enum DebugFlags {
DEBUG_ALL = 0xFF
};
enum EndstopEnum {
X_MIN,
Y_MIN,
Z_MIN,
Z_MIN_PROBE,
X_MAX,
Y_MAX,
Z_MAX,
X2_MIN,
X2_MAX,
Y2_MIN,
Y2_MAX,
Z2_MIN,
Z2_MAX
};
#if ENABLED(EMERGENCY_PARSER)
enum e_parser_state {
state_RESET,
state_N,
state_M,
state_M1,
state_M10,
state_M108,
state_M11,
state_M112,
state_M4,
state_M41,
state_M410,
state_IGNORE // to '\n'
};
#endif
#if ENABLED(ADVANCED_PAUSE_FEATURE)
enum AdvancedPauseMenuResponse {
enum AdvancedPauseMenuResponse : char {
ADVANCED_PAUSE_RESPONSE_WAIT_FOR,
ADVANCED_PAUSE_RESPONSE_EXTRUDE_MORE,
ADVANCED_PAUSE_RESPONSE_RESUME_PRINT
};
#if ENABLED(ULTIPANEL)
enum AdvancedPauseMessage {
enum AdvancedPauseMessage : char {
ADVANCED_PAUSE_MESSAGE_INIT,
ADVANCED_PAUSE_MESSAGE_UNLOAD,
ADVANCED_PAUSE_MESSAGE_INSERT,
ADVANCED_PAUSE_MESSAGE_LOAD,
ADVANCED_PAUSE_MESSAGE_EXTRUDE,
ADVANCED_PAUSE_MESSAGE_PURGE,
#if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE)
ADVANCED_PAUSE_MESSAGE_CONTINUOUS_PURGE,
#endif
ADVANCED_PAUSE_MESSAGE_OPTION,
ADVANCED_PAUSE_MESSAGE_RESUME,
ADVANCED_PAUSE_MESSAGE_STATUS,
@@ -139,6 +115,12 @@ enum EndstopEnum {
ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT
};
#endif
enum AdvancedPauseMode : char {
ADVANCED_PAUSE_MODE_PAUSE_PRINT,
ADVANCED_PAUSE_MODE_LOAD_FILAMENT,
ADVANCED_PAUSE_MODE_UNLOAD_FILAMENT
};
#endif
/**
@@ -146,7 +128,7 @@ enum EndstopEnum {
* Marlin sends messages if blocked or busy
*/
#if ENABLED(HOST_KEEPALIVE_FEATURE)
enum MarlinBusyState {
enum MarlinBusyState : char {
NOT_BUSY, // Not in a handler
IN_HANDLER, // Processing a GCode
IN_PROCESS, // Known to be blocking command input (as in G29)
@@ -158,12 +140,12 @@ enum EndstopEnum {
/**
* SD Card
*/
enum LsAction { LS_SerialPrint, LS_Count, LS_GetFilename };
enum LsAction : char { LS_SerialPrint, LS_Count, LS_GetFilename };
/**
* Ultra LCD
*/
enum LCDViewAction {
enum LCDViewAction : char {
LCDVIEW_NONE,
LCDVIEW_REDRAW_NOW,
LCDVIEW_CALL_REDRAW_NEXT,
@@ -175,7 +157,7 @@ enum LCDViewAction {
* Dual X Carriage modes. A Dual Nozzle can also do duplication.
*/
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
enum DualXMode {
enum DualXMode : char {
DXC_FULL_CONTROL_MODE, // DUAL_X_CARRIAGE only
DXC_AUTO_PARK_MODE, // DUAL_X_CARRIAGE only
DXC_DUPLICATION_MODE
@@ -187,7 +169,7 @@ enum LCDViewAction {
* (and "canned cycles" - not a current feature)
*/
#if ENABLED(CNC_WORKSPACE_PLANES)
enum WorkspacePlane { PLANE_XY, PLANE_ZX, PLANE_YZ };
enum WorkspacePlane : char { PLANE_XY, PLANE_ZX, PLANE_YZ };
#endif
#endif // __ENUM_H__

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -79,22 +79,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
//#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -196,11 +201,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -232,6 +237,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -245,6 +259,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -253,7 +268,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -263,6 +279,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -284,14 +301,15 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 7
#define TEMP_SENSOR_1 7
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 7
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -341,7 +359,7 @@
#define PIDTEMP
#define BANG_MAX 70 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX 74 // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -354,52 +372,59 @@
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Buda 2.0 on 24V
#define DEFAULT_Kp 6
#define DEFAULT_Ki .3
#define DEFAULT_Kd 125
#define DEFAULT_Kp 6
#define DEFAULT_Ki .3
#define DEFAULT_Kd 125
// Buda 2.0 on 12V
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.01
//#define DEFAULT_Kd 114
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.01
//#define DEFAULT_Kd 114
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
//#define DEFAULT_Kd 114
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
//#define DEFAULT_Kd 114
// MakerGear
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
// Mendel Parts V9 on 12V
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
#define PIDTEMPBED
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 206 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -407,42 +432,47 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
//24V 360W silicone heater from NPH on 3mm borosilicate (TAZ 2.2+)
#define DEFAULT_bedKp 20
#define DEFAULT_bedKi 5
#define DEFAULT_bedKd 275
#define DEFAULT_bedKp 20
#define DEFAULT_bedKi 5
#define DEFAULT_bedKd 275
//12v 400W silicone heater from QUDB into 3mm borosilicate (TAZ 1.0+)
//from pidautotune
//#define DEFAULT_bedKp 650
//#define DEFAULT_bedKi 60
//#define DEFAULT_bedKd 1800
//#define DEFAULT_bedKp 650
//#define DEFAULT_bedKi 60
//#define DEFAULT_bedKd 1800
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
//#define DEFAULT_bedKp 10.00
//#define DEFAULT_bedKi .023
//#define DEFAULT_bedKd 305.4
//#define DEFAULT_bedKp 10.00
//#define DEFAULT_bedKi .023
//#define DEFAULT_bedKd 305.4
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
@@ -497,11 +527,10 @@
//#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -518,12 +547,55 @@
#define X_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the probe.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -591,6 +663,16 @@
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 10.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -641,6 +723,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -651,7 +734,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -670,6 +753,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -707,13 +793,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -737,6 +826,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 5 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -772,9 +865,6 @@
#define INVERT_Y_DIR true
#define INVERT_Z_DIR false
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -788,6 +878,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -820,7 +912,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -828,7 +920,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -836,18 +928,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -895,6 +992,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -917,12 +1020,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -934,13 +1037,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -963,17 +1063,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -982,27 +1071,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -1011,8 +1096,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
//#define PROBE_PT_1_X 15
//#define PROBE_PT_1_Y 180
//#define PROBE_PT_2_X 15
//#define PROBE_PT_2_Y 20
//#define PROBE_PT_3_X 170
//#define PROBE_PT_3_Y 20
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -1024,6 +1122,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
//#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1297,11 +1400,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1329,19 +1432,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1368,6 +1458,15 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
@@ -1432,12 +1531,18 @@
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1455,40 +1560,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1497,28 +1568,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1526,33 +1575,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
//#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1568,12 +1612,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1598,6 +1643,83 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1613,24 +1735,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1646,6 +1760,13 @@
//
//#define CR10_STOCKDISPLAY
//
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
@@ -1655,11 +1776,40 @@
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1719,7 +1869,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1784,9 +1934,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
//#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,4,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 4, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1076,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1244,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1482,7 +1554,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1566,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1598,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1608,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1648,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -79,22 +79,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
//#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -196,11 +201,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -232,6 +237,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -245,6 +259,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -253,7 +268,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -263,6 +279,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -284,7 +301,7 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@@ -292,6 +309,7 @@
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 1
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -341,7 +359,7 @@
#define PIDTEMP
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -355,42 +373,49 @@
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114
// MakerGear
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
// Mendel Parts V9 on 12V
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
//#define PIDTEMPBED
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -399,30 +424,35 @@
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 800
@@ -477,11 +507,10 @@
#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -492,18 +521,61 @@
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define X_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define X_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define X_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Y_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -571,6 +643,16 @@
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -621,6 +703,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -631,7 +714,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -650,6 +733,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -687,13 +773,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER 10 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -717,6 +806,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 5 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -752,9 +845,6 @@
#define INVERT_Y_DIR true
#define INVERT_Z_DIR false
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -768,6 +858,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -800,7 +892,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -808,7 +900,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -816,18 +908,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -875,6 +972,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -897,12 +1000,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -914,13 +1017,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -943,17 +1043,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -962,27 +1051,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -991,8 +1076,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
//#define PROBE_PT_1_X 15
//#define PROBE_PT_1_Y 180
//#define PROBE_PT_2_X 15
//#define PROBE_PT_2_Y 20
//#define PROBE_PT_3_X 170
//#define PROBE_PT_3_Y 20
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -1004,6 +1102,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
//#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1277,11 +1380,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1309,19 +1412,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1348,19 +1438,28 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
// This option overrides the default number of encoder pulses needed to
// produce one step. Should be increased for high-resolution encoders.
//
//#define ENCODER_PULSES_PER_STEP 1
//#define ENCODER_PULSES_PER_STEP 4
//
// Use this option to override the number of step signals required to
// move between next/prev menu items.
//
//#define ENCODER_STEPS_PER_MENU_ITEM 5
//#define ENCODER_STEPS_PER_MENU_ITEM 1
/**
* Encoder Direction Options
@@ -1412,12 +1511,18 @@
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1435,40 +1540,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1477,28 +1548,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1506,33 +1555,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
//#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1548,12 +1592,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1578,6 +1623,83 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1593,24 +1715,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1626,6 +1740,13 @@
//
//#define CR10_STOCKDISPLAY
//
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
@@ -1635,11 +1756,40 @@
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1699,7 +1849,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1764,9 +1914,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
//#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1076,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1244,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1482,7 +1554,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1566,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1598,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1608,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1648,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -79,22 +79,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
//#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -197,11 +202,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -233,6 +238,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -246,6 +260,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -254,7 +269,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -264,6 +280,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -285,7 +302,7 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
@@ -293,6 +310,7 @@
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 5
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -342,7 +360,7 @@
#define PIDTEMP
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -356,48 +374,55 @@
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker
//#define DEFAULT_Kp 21.0
//#define DEFAULT_Ki 1.25
//#define DEFAULT_Kd 86.0
//#define DEFAULT_Kp 21.0
//#define DEFAULT_Ki 1.25
//#define DEFAULT_Kd 86.0
// MakerGear
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
// Mendel Parts V9 on 12V
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
// ANET A8 Standard Extruder at 210 Degree Celsius and 100% Fan
//(measured after M106 S255 with M303 E0 S210 C8)
#define DEFAULT_Kp 21.0
#define DEFAULT_Ki 1.25
#define DEFAULT_Kd 86.0
#define DEFAULT_Kp 21.0
#define DEFAULT_Ki 1.25
#define DEFAULT_Kd 86.0
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
//#define PIDTEMPBED
#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -406,30 +431,35 @@
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 160 // 160 guards against false tripping when the extruder fan kicks on.
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
@@ -484,11 +514,10 @@
//#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -507,10 +536,53 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -578,6 +650,16 @@
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -628,6 +710,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -638,7 +721,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -657,6 +740,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -694,13 +780,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER 0 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 6000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -724,6 +813,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 5 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -759,9 +852,6 @@
#define INVERT_Y_DIR false
#define INVERT_Z_DIR true
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -775,6 +865,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -807,7 +899,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -815,7 +907,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -823,18 +915,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -882,6 +979,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -904,12 +1007,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -921,13 +1024,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 190
#define FRONT_PROBE_BED_POSITION 15
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -950,17 +1050,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 20
#define ABL_PROBE_PT_1_Y 160
#define ABL_PROBE_PT_2_X 20
#define ABL_PROBE_PT_2_Y 10
#define ABL_PROBE_PT_3_X 180
#define ABL_PROBE_PT_3_Y 10
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -969,27 +1058,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -998,8 +1083,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
#define PROBE_PT_1_X 20
#define PROBE_PT_1_Y 160
#define PROBE_PT_2_X 20
#define PROBE_PT_2_Y 10
#define PROBE_PT_3_X 180
#define PROBE_PT_3_Y 10
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -1011,6 +1109,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
//#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1284,11 +1387,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1316,19 +1419,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1355,19 +1445,28 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
// This option overrides the default number of encoder pulses needed to
// produce one step. Should be increased for high-resolution encoders.
//
//#define ENCODER_PULSES_PER_STEP 1
//#define ENCODER_PULSES_PER_STEP 4
//
// Use this option to override the number of step signals required to
// move between next/prev menu items.
//
//#define ENCODER_STEPS_PER_MENU_ITEM 5
//#define ENCODER_STEPS_PER_MENU_ITEM 1
/**
* Encoder Direction Options
@@ -1419,12 +1518,18 @@
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1442,40 +1547,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1484,30 +1555,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
// Note: Details on connecting to the Anet V1.0 controller are in the file pins_ANET_10.h
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1515,33 +1562,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
//#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1557,12 +1599,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1587,6 +1630,85 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
// Note: Details on connecting to the Anet V1.0 controller are in the file pins_ANET_10.h
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1602,24 +1724,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1635,6 +1749,13 @@
//
//#define CR10_STOCKDISPLAY
//
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
@@ -1644,11 +1765,40 @@
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1708,7 +1858,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1773,9 +1923,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
//#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1076,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1244,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1482,7 +1554,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1566,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1598,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1608,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1648,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -79,22 +79,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
//#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -126,9 +131,6 @@
// Displayed in the LCD "Ready" message
#define CUSTOM_MACHINE_NAME "HEPHESTOS"
// Added for BQ
#define SOURCE_CODE_URL "http://www.bq.com/gb/downloads-prusa-i3-hephestos.html"
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
// 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"
@@ -199,11 +201,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -235,6 +237,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -248,6 +259,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -256,7 +268,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -266,6 +279,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -287,7 +301,7 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@@ -295,6 +309,7 @@
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 0
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -344,7 +359,7 @@
#define PIDTEMP
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -356,32 +371,39 @@
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
// Hephestos i3
#define DEFAULT_Kp 23.05
#define DEFAULT_Ki 2.00
#define DEFAULT_Kd 66.47
#define DEFAULT_Kp 23.05
#define DEFAULT_Ki 2.00
#define DEFAULT_Kd 66.47
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
//#define PIDTEMPBED
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -390,30 +412,35 @@
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
@@ -468,11 +495,10 @@
//#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -491,10 +517,53 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -562,6 +631,16 @@
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -612,6 +691,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -622,7 +702,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -641,6 +721,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -678,13 +761,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -708,6 +794,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 5 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -743,9 +833,6 @@
#define INVERT_Y_DIR false
#define INVERT_Z_DIR true
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -759,6 +846,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -791,7 +880,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -799,7 +888,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -807,18 +896,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -866,6 +960,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -888,12 +988,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -905,13 +1005,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -934,17 +1031,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -953,27 +1039,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -982,8 +1064,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
//#define PROBE_PT_1_X 15
//#define PROBE_PT_1_Y 180
//#define PROBE_PT_2_X 15
//#define PROBE_PT_2_Y 20
//#define PROBE_PT_3_X 170
//#define PROBE_PT_3_Y 20
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -995,6 +1090,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
//#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1268,11 +1368,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1300,19 +1400,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1339,19 +1426,28 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
// This option overrides the default number of encoder pulses needed to
// produce one step. Should be increased for high-resolution encoders.
//
//#define ENCODER_PULSES_PER_STEP 1
//#define ENCODER_PULSES_PER_STEP 4
//
// Use this option to override the number of step signals required to
// move between next/prev menu items.
//
//#define ENCODER_STEPS_PER_MENU_ITEM 5
//#define ENCODER_STEPS_PER_MENU_ITEM 1
/**
* Encoder Direction Options
@@ -1403,12 +1499,18 @@
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1426,40 +1528,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1468,28 +1536,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1497,33 +1543,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
//#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1539,12 +1580,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1569,6 +1611,83 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1584,24 +1703,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1617,6 +1728,13 @@
//
//#define CR10_STOCKDISPLAY
//
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
@@ -1626,11 +1744,40 @@
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1690,7 +1837,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1755,9 +1902,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
//#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1076,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1244,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1482,7 +1554,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1566,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1598,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1608,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1648,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

File diff suppressed because it is too large Load Diff

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -161,20 +172,22 @@
// Extruder runout prevention.
// If the machine is idle and the temperature over MINTEMP
// then extrude some filament every couple of SECONDS.
#define EXTRUDER_RUNOUT_PREVENT
//#define EXTRUDER_RUNOUT_PREVENT
#if ENABLED(EXTRUDER_RUNOUT_PREVENT)
#define EXTRUDER_RUNOUT_MINTEMP 170
#define EXTRUDER_RUNOUT_SECONDS 60
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30
#define EXTRUDER_RUNOUT_SPEED 1500 // mm/m
#define EXTRUDER_RUNOUT_EXTRUDE 5 // mm
#endif
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -193,12 +206,22 @@
// When first starting the main fan, run it at full speed for the
// given number of milliseconds. This gets the fan spinning reliably
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
#define FAN_KICKSTART_TIME 800
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -351,13 +384,16 @@
// Homing hits each endstop, retracts by these distances, then does a slower bump.
#define X_HOME_BUMP_MM 5
#define Y_HOME_BUMP_MM 5
#define Z_HOME_BUMP_MM 2
#define Z_HOME_BUMP_MM 1
#define HOMING_BUMP_DIVISOR { 2, 2, 4 } // Re-Bump Speed Divisor (Divides the Homing Feedrate)
#define QUICK_HOME // If homing includes X and Y, do a diagonal move initially
// When G28 is called, this option will make Y home before X
#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -374,10 +410,10 @@
// Default stepper release if idle. Set to 0 to deactivate.
// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true.
// Time can be set by M18 and M84.
#define DEFAULT_STEPPER_DEACTIVE_TIME 120
#define DISABLE_INACTIVE_X true
#define DISABLE_INACTIVE_Y true
#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished.
#define DEFAULT_STEPPER_DEACTIVE_TIME 300
#define DISABLE_INACTIVE_X false
#define DISABLE_INACTIVE_Y false
#define DISABLE_INACTIVE_Z false // set to false if the nozzle will fall down on your printed part when print has finished.
#define DISABLE_INACTIVE_E true
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
@@ -388,7 +424,7 @@
// @section lcd
#if ENABLED(ULTIPANEL)
#define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel
#define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 60 } // Feedrates for manual moves along X, Y, Z, E from panel
//#define ULTIPANEL_FEEDMULTIPLY // Comment to disable setting feedrate multiplier via encoder
#endif
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -434,7 +486,15 @@
* M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2
*/
//#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps
#define DIGIPOT_MOTOR_CURRENT { 150, 170, 180, 190, 180 } // Values 0-255 (bq ZUM Mega 3D (default): X = 150 [~1.17A]; Y = 170 [~1.33A]; Z = 180 [~1.41A]; E0 = 190 [~1.49A])
#define DIGIPOT_MOTOR_CURRENT { 170, 170, 180, 190, 180 } // Values 0-255
//
// bq ZUM Mega 3D defaults:
// X = 150 [~1.17A]
// Y = 170 [~1.33A]
// Z = 180 [~1.41A]
// E0 = 190 [~1.49A]
//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis
// Use an I2C based DIGIPOT (e.g., Azteeg X3 Pro)
@@ -454,24 +514,25 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
//=============================Additional Features===========================
//===========================================================================
//#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
//#define ENCODER_10X_STEPS_PER_SEC 75 // If the encoder steps per sec exceeds this value, multiply steps moved x10 to quickly advance the value
//#define ENCODER_100X_STEPS_PER_SEC 160 // If the encoder steps per sec exceeds this value, multiply steps moved x100 to really quickly advance the value
#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly
#define ENCODER_10X_STEPS_PER_SEC 30 // If the encoder steps per sec exceeds this value, multiply steps moved x10 to quickly advance the value
#define ENCODER_100X_STEPS_PER_SEC 50 // If the encoder steps per sec exceeds this value, multiply steps moved x100 to really quickly advance the value
//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
//#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
// @section lcd
// Include a page of printer information in the LCD Main Menu
#define LCD_INFO_MENU
//#define LCD_INFO_MENU
// Scroll a longer status message into view
#define STATUS_MESSAGE_SCROLLING
@@ -480,7 +541,21 @@
#define LCD_DECIMAL_SMALL_XY
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
#define LCD_TIMEOUT_TO_STATUS 60000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
@@ -508,8 +583,8 @@
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
#define SD_DETECT_INVERTED
#define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished
#define SD_FINISHED_RELEASECOMMAND "M104 S0\nM84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
#define SD_FINISHED_STEPPERRELEASE false // Disable steppers when SD Print is finished
#define SD_FINISHED_RELEASECOMMAND "G27 P0" // You might want to keep the z enabled so your bed stays in place.
// Reverse SD sort to show "more recent" files first, according to the card's FAT.
// Since the FAT gets out of order with usage, SDCARD_SORT_ALPHA is recommended.
@@ -518,6 +593,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,27 +645,8 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
#define LONG_FILENAME_HOST_SUPPORT
//#define LONG_FILENAME_HOST_SUPPORT
// Enable this option to scroll long filenames in the SD card menu
//#define SCROLL_LONG_FILENAMES
@@ -595,6 +665,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,19 +685,22 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
//#define XYZ_HOLLOW_FRAME
// Enable to save many cycles by drawing a hollow frame on Menu Screens
#define MENU_HOLLOW_FRAME
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
#define USE_BIG_EDIT_FONT
//#define USE_BIG_EDIT_FONT
// A smaller font may be used on the Info Screen. Costs 2300 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
#define USE_SMALL_INFOFONT
//#define USE_SMALL_INFOFONT
// Enable this option and reduce the value to optimize screen updates.
// The normal delay is 10µs. Use the lowest value that still gives a reliable display.
@@ -631,6 +709,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -655,68 +752,44 @@
*
* Warning: Does not respect endstops!
*/
//#define BABYSTEPPING
#define BABYSTEPPING
#if ENABLED(BABYSTEPPING)
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
#define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion.
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
#define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds.
// Note: Extra time may be added to mitigate controller latency.
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
//#define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA!
#define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way
#define BABYSTEP_MULTIPLICATOR 2 // Babysteps are very small. Increase for faster motion.
//#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping
//#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping.
#define DOUBLECLICK_MAX_INTERVAL 1500 // Maximum interval between clicks, in milliseconds.
// Note: Extra time may be added to mitigate controller latency.
//#define BABYSTEP_ZPROBE_GFX_OVERLAY // Enable graphical overlay on Z-offset editor
#endif
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -730,7 +803,7 @@
//
// G2/G3 Arc Support
//
#define ARC_SUPPORT // Disable this feature to save ~3226 bytes
//#define ARC_SUPPORT // Disable this feature to save ~3226 bytes
#if ENABLED(ARC_SUPPORT)
#define MM_PER_ARC_SEGMENT 1 // Length of each arc segment
#define N_ARC_CORRECTION 25 // Number of intertpolated segments between corrections
@@ -751,9 +824,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -769,7 +879,7 @@
// The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2 (e.g. 8, 16, 32) because shifts and ors are used to do the ring-buffering.
#if ENABLED(SDSUPPORT)
#define BLOCK_BUFFER_SIZE 32 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 64 // maximize block buffer
#endif
@@ -815,13 +925,13 @@
// enter the serial receive buffer, so they cannot be blocked.
// Currently handles M108, M112, M410
// Does not work on boards using AT90USB (USBCON) processors!
#define EMERGENCY_PARSER
//#define EMERGENCY_PARSER
// Bad Serial-connections can miss a received command by sending an 'ok'
// Therefore some clients abort after 30 seconds in a timeout.
// Some other clients start sending commands while receiving a 'wait'.
// This "wait" is only sent when the buffer is empty. 1 second is a good value here.
//#define NO_TIMEOUTS 1000 // Milliseconds
#define NO_TIMEOUTS 1000 // Milliseconds
// Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary.
#define ADVANCED_OK
@@ -878,53 +988,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1084,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1143,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1201,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1224,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1252,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1482,7 +1562,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1574,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1606,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1616,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1656,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

View File

@@ -1,22 +1,29 @@
# Example Configuration for BQ [Hephestos 2](http://www.bq.com/uk/hephestos-2)
This configuration file is based on the original configuration file shipped with the heavily modified Marlin fork by BQ. The original firmware and configuration file can be found at [BQ Github repository](https://github.com/bq/Marlin).
Based on the original configuration file shipped with the heavily modified Marlin fork by BQ.
The forked firmware and configuration files can be found at the [BQ Github repository](https://github.com/bq/Marlin).
NOTE: The look and feel of the Hephestos 2 while navigating the LCD menu will change by using the original Marlin firmware.
NOTE: The look and feel of the LCD menu will change dramatically when using the original Marlin firmware.
## Changelog
* 2016/03/01 - Initial release
* 2018/05/30 - Configuration updated to the latest Marlin version (43a55a9af).
ABL Bilinear 5x5 is active by default.
* 2016/03/21 - Activated 4-point auto leveling by default
Updated miscellaneous z-probe values
* 2017/07/06 - Configuration updated to the latest Marlin version and added support for the
official BQ heated bed upgrade kit.
* 2016/06/21 - Disabled hot bed related options
Activated software endstops
SD printing now disables the heater when finished
* 2016/12/13 - Configuration updated to the latest Marlin version.
* 2016/07/13 - Update the `DEFAULT_AXIS_STEPS_PER_UNIT` for the Z axis
Increased the `DEFAULT_XYJERK`
* 2016/07/13 - Configuration updated to the latest Marlin version.
* 2016/12/13 - Configuration updated.
* 2016/06/21 - Disabled heated bed related options, activated software endstops and SD printing now
disables the heater when finishes printing.
* 2017/07/06 - Configuration updated to the latest Marlin version.
Added support for the official BQ heated bed kit.
* 2016/03/21 - Activated 4-point auto leveling by default and updated miscellaneous z-probe values.
* 2016/03/01 - The first release of Marlin's configuration file for the
BQ Hephestos 2 3D printer.
## Support
This configuration should work easily with the stock Hephestos 2, nevertheless if you encounter any
issues you may contact me on [Github](https://github.com/jbrazio), [Twitter](https://twitter.com/jbrazio) or by mail.

View File

@@ -21,83 +21,80 @@
*/
/**
* Custom Bitmap for splashscreen
* Custom Boot Screen bitmap
*
* You may use one of the following tools to generate the C++ bitmap array from
* a black and white image:
* Place this file in the root with your configuration files
* and enable SHOW_CUSTOM_BOOTSCREEN in Configuration.h.
*
* - http://www.marlinfw.org/tools/u8glib/converter.html
* - http://www.digole.com/tools/PicturetoC_Hex_converter.php
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#include <avr/pgmspace.h>
#define CUSTOM_BOOTSCREEN_TIMEOUT 2500
#define CUSTOM_BOOTSCREEN_BMPWIDTH 62
#define CUSTOM_BOOTSCREEN_BMPHEIGHT 64
#define CUSTOM_BOOTSCREEN_BMPWIDTH 64
const unsigned char custom_start_bmp[512] PROGMEM = {
0x00, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x00,
0x00, 0x03, 0xC0, 0x0F, 0xF0, 0x07, 0x80, 0x00,
0x00, 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0xC0, 0x00,
0x00, 0x0F, 0xF0, 0x03, 0xC0, 0x1F, 0xE0, 0x00,
0x00, 0x1F, 0xF8, 0x00, 0x00, 0x3F, 0xF0, 0x00,
0x00, 0x1F, 0xF8, 0x00, 0x00, 0x3F, 0xF0, 0x00,
0x00, 0x1F, 0xF8, 0x00, 0x00, 0x3F, 0xF0, 0x00,
0x00, 0x1F, 0xF8, 0x00, 0x00, 0x3F, 0xF0, 0x00,
0x00, 0x1F, 0xF8, 0x00, 0x00, 0x3F, 0xF0, 0x00,
0x00, 0x0F, 0xF0, 0x00, 0x00, 0x1F, 0xE0, 0x00,
0x00, 0x07, 0xE0, 0x00, 0x00, 0x0F, 0xC0, 0x00,
0x00, 0x03, 0xC0, 0x00, 0x00, 0x07, 0x80, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF8,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFC,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFC,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFC,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFC,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFC,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xFC,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFC,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF8,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF0,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x1E, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00,
0x3F, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00,
0x7F, 0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00,
0xFF, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00,
0xFF, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00,
0xFF, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00,
0xFF, 0xC0, 0x00, 0x00, 0xF7, 0xC0, 0x1F, 0x80,
0xFF, 0xC0, 0x00, 0x00, 0xFF, 0xF0, 0x7F, 0xC0,
0x7F, 0x80, 0x00, 0x00, 0xFF, 0xF8, 0xFF, 0xE0,
0x3F, 0x00, 0x00, 0x00, 0xFC, 0xF8, 0xF0, 0xF8,
0x1E, 0x00, 0x00, 0x00, 0xF8, 0x7D, 0xE0, 0x78,
0x00, 0x00, 0x00, 0x00, 0xF0, 0x3D, 0xE0, 0x78,
0x00, 0x00, 0x00, 0x00, 0xF0, 0x3D, 0xE0, 0x78,
0x00, 0x00, 0x00, 0x00, 0xF0, 0x3D, 0xE0, 0x78,
0x00, 0x00, 0x00, 0x00, 0xF0, 0x3D, 0xE0, 0x78,
0x00, 0x00, 0x00, 0x00, 0xF0, 0x3D, 0xE0, 0x78,
0x00, 0x00, 0x00, 0x00, 0xF0, 0x3D, 0xE0, 0x78,
0x00, 0x00, 0x00, 0x00, 0xF8, 0x79, 0xF0, 0xF8,
0x00, 0x00, 0x00, 0x00, 0xFF, 0xF8, 0xFF, 0xF8,
0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x7F, 0xF8,
0x00, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x3F, 0xF8,
0x00, 0x00, 0x00, 0x00, 0x03, 0x80, 0x0E, 0x78,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78,
const unsigned char custom_start_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000011,B11110000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11111000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11111000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00001111,B11111100,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00001111,B11111100,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11111000,B00000000,B00000000,B00000000,
B00000000,B00000000,B11111000,B00000111,B11111000,B00000111,B11000000,B00000000,
B00000000,B00000001,B11111100,B00000011,B11110000,B00001111,B11100000,B00000000,
B00000000,B00000011,B11111110,B00000000,B11000000,B00011111,B11110000,B00000000,
B00000000,B00000011,B11111110,B00000000,B00000000,B00011111,B11110000,B00000000,
B00000000,B00000011,B11111110,B00000000,B00000000,B00011111,B11110000,B00000000,
B00000000,B00000011,B11111110,B00000000,B00000000,B00011111,B11110000,B00000000,
B00000000,B00000011,B11111100,B00000000,B00000000,B00001111,B11100000,B00000000,
B00000000,B00000001,B11111000,B00000000,B00000000,B00001111,B11100000,B00000000,
B00000000,B00000000,B01110000,B00000000,B00000000,B00000011,B10000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111100,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111100,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111100,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111100,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111100,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B11111100,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000001,B11111000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00001111,B10000000,B00000000,B00000000,B01110000,B00000000,B00000000,B00000000,
B00011111,B11000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,
B00111111,B11000000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,
B00111111,B11100000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,
B00111111,B11100000,B00000000,B00000000,B01111000,B00000000,B00000000,B00000000,
B00111111,B11100000,B00000000,B00000000,B01111011,B11000000,B00001111,B00000000,
B00111111,B11000000,B00000000,B00000000,B01111111,B11110000,B00111111,B11000000,
B00011111,B10000000,B00000000,B00000000,B01111111,B11111000,B01111111,B11100000,
B00001111,B00000000,B00000000,B00000000,B01111110,B11111100,B11111001,B11110000,
B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B11100000,B11110000,
B00000000,B00000000,B00000000,B00000000,B01111000,B00011101,B11100000,B01110000,
B00000000,B00000000,B00000000,B00000000,B01111000,B00011101,B11100000,B01110000,
B00000000,B00000000,B00000000,B00000000,B01111000,B00011101,B11100000,B01110000,
B00000000,B00000000,B00000000,B00000000,B01111000,B00011101,B11100000,B01110000,
B00000000,B00000000,B00000000,B00000000,B01111000,B00011101,B11100000,B01110000,
B00000000,B00000000,B00000000,B00000000,B01111000,B00111100,B11100000,B11110000,
B00000000,B00000000,B00000000,B00000000,B01111100,B01111100,B11111001,B11110000,
B00000000,B00000000,B00000000,B00000000,B00011111,B11111000,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00001111,B11110000,B01111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000111,B11100000,B00011111,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000
};

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -79,22 +79,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
//#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -126,9 +131,6 @@
// Displayed in the LCD "Ready" message
#define CUSTOM_MACHINE_NAME "WITBOX"
// Added for BQ
#define SOURCE_CODE_URL "http://www.bq.com/gb/downloads-witbox.html"
// Define this to set a unique identifier for this printer, (Used by some programs to differentiate between machines)
// 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"
@@ -199,11 +201,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -235,6 +237,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -248,6 +259,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -256,7 +268,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -266,6 +279,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -287,7 +301,7 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@@ -295,6 +309,7 @@
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 0
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -344,7 +359,7 @@
#define PIDTEMP
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -356,32 +371,39 @@
// is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
// Witbox
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114
#define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
//#define PIDTEMPBED
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -390,30 +412,35 @@
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
#define DEFAULT_bedKp 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
@@ -468,11 +495,10 @@
#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -491,10 +517,53 @@
#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -562,6 +631,16 @@
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -612,6 +691,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -622,7 +702,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -641,6 +721,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -678,13 +761,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -708,6 +794,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 5 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -743,9 +833,6 @@
#define INVERT_Y_DIR false
#define INVERT_Z_DIR true
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -759,6 +846,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -791,7 +880,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -799,7 +888,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -807,18 +896,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -866,6 +960,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -888,12 +988,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -905,13 +1005,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -934,17 +1031,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -953,27 +1039,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -982,8 +1064,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
//#define PROBE_PT_1_X 15
//#define PROBE_PT_1_Y 180
//#define PROBE_PT_2_X 15
//#define PROBE_PT_2_Y 20
//#define PROBE_PT_3_X 170
//#define PROBE_PT_3_Y 20
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -995,6 +1090,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
//#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1268,11 +1368,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1300,19 +1400,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1339,19 +1426,28 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
// This option overrides the default number of encoder pulses needed to
// produce one step. Should be increased for high-resolution encoders.
//
//#define ENCODER_PULSES_PER_STEP 1
//#define ENCODER_PULSES_PER_STEP 4
//
// Use this option to override the number of step signals required to
// move between next/prev menu items.
//
//#define ENCODER_STEPS_PER_MENU_ITEM 5
//#define ENCODER_STEPS_PER_MENU_ITEM 1
/**
* Encoder Direction Options
@@ -1403,12 +1499,18 @@
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1426,40 +1528,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1468,28 +1536,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1497,33 +1543,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1539,12 +1580,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1569,6 +1611,83 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1584,24 +1703,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1617,6 +1728,13 @@
//
//#define CR10_STOCKDISPLAY
//
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
@@ -1626,11 +1744,40 @@
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1690,7 +1837,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1755,9 +1902,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
//#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 2 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1076,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1244,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1482,7 +1554,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1566,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1598,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1608,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1648,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -79,22 +79,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -197,11 +202,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -233,6 +238,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -246,6 +260,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -254,7 +269,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -264,6 +280,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -285,7 +302,7 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1
@@ -293,6 +310,7 @@
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 1
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -342,7 +360,7 @@
#define PIDTEMP
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -356,42 +374,49 @@
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Cartesio extruderV6 40W Normal
#define DEFAULT_Kp 18
#define DEFAULT_Ki 1
#define DEFAULT_Kd 100
#define DEFAULT_Kp 18
#define DEFAULT_Ki 1
#define DEFAULT_Kd 100
// Cartesio extruderV6 40W Volcano
//#define DEFAULT_Kp 50
//#define DEFAULT_Ki 9
//#define DEFAULT_Kd 70
//#define DEFAULT_Kp 50
//#define DEFAULT_Ki 9
//#define DEFAULT_Kd 70
// Cartesio extruderV6 40W Cyclops
//#define DEFAULT_Kp 18
//#define DEFAULT_Ki 1
//#define DEFAULT_Kd 100
//#define DEFAULT_Kp 18
//#define DEFAULT_Ki 1
//#define DEFAULT_Kd 100
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
#define PIDTEMPBED
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -399,29 +424,34 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
//24V 500W silicone heater on to 4mm glass CartesioW
#define DEFAULT_bedKp 390
#define DEFAULT_bedKi 70
#define DEFAULT_bedKd 546
#define DEFAULT_bedKp 390
#define DEFAULT_bedKi 70
#define DEFAULT_bedKd 546
//24V 250W silicone heater on to 4mm glass CartesioM
//#define DEFAULT_bedKp 303
//#define DEFAULT_bedKi 42
//#define DEFAULT_bedKd 539
//#define DEFAULT_bedKp 303
//#define DEFAULT_bedKi 42
//#define DEFAULT_bedKd 539
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 200
@@ -476,11 +506,10 @@
//#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -497,12 +526,55 @@
#define X_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Y_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the probe.
#define Z_MIN_PROBE_ENDSTOP_INVERTING true // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -570,6 +642,16 @@
#define DEFAULT_ZJERK 0.3
#define DEFAULT_EJERK 5.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -620,6 +702,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -630,7 +713,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -649,6 +732,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -686,13 +772,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER 10 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -716,6 +805,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 15 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 5 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 5 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -751,9 +844,6 @@
#define INVERT_Y_DIR true
#define INVERT_Z_DIR false
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -767,6 +857,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 4 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -799,7 +891,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -807,7 +899,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -815,18 +907,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -874,6 +971,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -896,12 +999,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -913,13 +1016,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -942,17 +1042,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -961,27 +1050,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -990,8 +1075,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
//#define PROBE_PT_1_X 15
//#define PROBE_PT_1_Y 180
//#define PROBE_PT_2_X 15
//#define PROBE_PT_2_Y 20
//#define PROBE_PT_3_X 170
//#define PROBE_PT_3_Y 20
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -1003,6 +1101,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
//#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1276,11 +1379,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1308,19 +1411,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1347,6 +1437,15 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
@@ -1411,12 +1510,18 @@
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100
#define LCD_FEEDBACK_FREQUENCY_HZ 1000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1434,40 +1539,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1476,28 +1547,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
#define REPRAPWORLD_KEYPAD
#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1505,33 +1554,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
//#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1547,12 +1591,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1577,6 +1622,83 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1592,24 +1714,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1625,6 +1739,13 @@
//
//#define CR10_STOCKDISPLAY
//
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
@@ -1634,11 +1755,40 @@
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
#define REPRAPWORLD_KEYPAD
#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1698,7 +1848,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1763,9 +1913,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 3.0
#define TEMP_SENSOR_AD595_GAIN 2.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 35
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
//#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#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
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 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 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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 1 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
//#define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 6 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
//#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1076,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1244,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1482,7 +1554,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1494,7 +1566,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1526,7 +1598,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1536,27 +1608,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1574,4 +1648,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

View File

@@ -21,83 +21,80 @@
*/
/**
* Custom Bitmap for splashscreen
* Custom Boot Screen bitmap
*
* You may use one of the following tools to generate the C++ bitmap array from
* a black and white image:
* Place this file in the root with your configuration files
* and enable SHOW_CUSTOM_BOOTSCREEN in Configuration.h.
*
* - http://www.marlinfw.org/tools/u8glib/converter.html
* - http://www.digole.com/tools/PicturetoC_Hex_converter.php
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#include <avr/pgmspace.h>
#define CUSTOM_BOOTSCREEN_TIMEOUT 2500
#define CUSTOM_BOOTSCREEN_BMPWIDTH 63
#define CUSTOM_BOOTSCREEN_BMPHEIGHT 64
#define CUSTOM_BOOTSCREEN_BMPWIDTH 64
const unsigned char custom_start_bmp[512] PROGMEM = {
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x3F, 0xFC, 0x00, 0x00, 0x00,
0x00, 0x00, 0x03, 0xFF, 0xFF, 0xC0, 0x00, 0x00,
0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xF0, 0x00, 0x00,
0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00,
0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00,
0x00, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00,
0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x0F, 0x07, 0x87, 0xFF, 0xFF, 0xE0, 0x00,
0x00, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xF1, 0x00,
0x01, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xF1, 0x80,
0x03, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xF1, 0x80,
0x07, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xE1, 0xC0,
0x07, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xE0,
0x0F, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xE0,
0x0F, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xF0,
0x1F, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xF0,
0x1F, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xE1, 0xF0,
0x3F, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xF1, 0xF8,
0x3F, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xF1, 0xF8,
0x3F, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xF1, 0xF8,
0x3F, 0x1F, 0x8F, 0xC7, 0xFF, 0xFF, 0xE1, 0xF8,
0x7F, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xFC,
0x7F, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xFC,
0x7F, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xFC,
0x7F, 0x1F, 0x8F, 0xC7, 0xC0, 0x00, 0x01, 0xFC,
0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x7F, 0x00, 0x00, 0x07, 0xC7, 0xE3, 0xF1, 0xFC,
0x7F, 0x00, 0x00, 0x07, 0xC7, 0xE3, 0xF1, 0xFC,
0x7F, 0x00, 0x00, 0x07, 0xC7, 0xE3, 0xF1, 0xFC,
0x3F, 0x0F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0xF8,
0x3F, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0xF8,
0x3F, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0xF8,
0x3F, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0xF8,
0x1F, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0xF0,
0x1F, 0x0F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0xF0,
0x1F, 0x00, 0x00, 0x07, 0xC7, 0xE3, 0xF1, 0xE0,
0x0F, 0x00, 0x00, 0x07, 0xC7, 0xE3, 0xF1, 0xE0,
0x0F, 0x00, 0x00, 0x07, 0xC7, 0xE3, 0xF1, 0xC0,
0x07, 0x0F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0xC0,
0x03, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0x80,
0x03, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF1, 0x00,
0x01, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF0, 0x00,
0x00, 0x1F, 0xFF, 0xFF, 0xC7, 0xE3, 0xF0, 0x00,
0x00, 0x0F, 0xFF, 0xFF, 0xC3, 0xC1, 0xE0, 0x00,
0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x00,
0x00, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00,
0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00,
0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x00,
0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xF0, 0x00, 0x00,
0x00, 0x00, 0x07, 0xFF, 0xFF, 0x80, 0x00, 0x00,
0x00, 0x00, 0x00, 0x7F, 0xF8, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
const unsigned char custom_start_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00111111,B11111100,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000011,B11111111,B11111111,B11000000,B00000000,B00000000,
B00000000,B00000000,B00011111,B11111111,B11111111,B11110000,B00000000,B00000000,
B00000000,B00000000,B01111111,B11111111,B11111111,B11111100,B00000000,B00000000,
B00000000,B00000000,B11111111,B11111111,B11111111,B11111111,B00000000,B00000000,
B00000000,B00000011,B11111111,B11111111,B11111111,B11111111,B10000000,B00000000,
B00000000,B00000111,B11111111,B11111111,B11111111,B11111111,B11000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11000000,B00000000,B00000000,B00000000,
B00000000,B00001111,B00000111,B10000111,B11111111,B11111111,B11100000,B00000000,
B00000000,B00011111,B10001111,B11000111,B11111111,B11111111,B11110001,B00000000,
B00000001,B00011111,B10001111,B11000111,B11111111,B11111111,B11110001,B10000000,
B00000011,B00011111,B10001111,B11000111,B11111111,B11111111,B11110001,B10000000,
B00000111,B00011111,B10001111,B11000111,B11111111,B11111111,B11100001,B11000000,
B00000111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11100000,
B00001111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11100000,
B00001111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11110000,
B00011111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11110000,
B00011111,B00011111,B10001111,B11000111,B11111111,B11111111,B11100001,B11110000,
B00111111,B00011111,B10001111,B11000111,B11111111,B11111111,B11110001,B11111000,
B00111111,B00011111,B10001111,B11000111,B11111111,B11111111,B11110001,B11111000,
B00111111,B00011111,B10001111,B11000111,B11111111,B11111111,B11110001,B11111000,
B00111111,B00011111,B10001111,B11000111,B11111111,B11111111,B11100001,B11111000,
B01111111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11111100,
B01111111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11111100,
B01111111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11111100,
B01111111,B00011111,B10001111,B11000111,B11000000,B00000000,B00000001,B11111100,
B01111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111100,
B01111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111100,
B01111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111100,
B01111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111100,
B01111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111100,
B01111111,B00000000,B00000000,B00000111,B11000111,B11100011,B11110001,B11111100,
B01111111,B00000000,B00000000,B00000111,B11000111,B11100011,B11110001,B11111100,
B01111111,B00000000,B00000000,B00000111,B11000111,B11100011,B11110001,B11111100,
B00111111,B00001111,B11111111,B11111111,B11000111,B11100011,B11110001,B11111000,
B00111111,B00011111,B11111111,B11111111,B11000111,B11100011,B11110001,B11111000,
B00111111,B00011111,B11111111,B11111111,B11000111,B11100011,B11110001,B11111000,
B00111111,B00011111,B11111111,B11111111,B11000111,B11100011,B11110001,B11111000,
B00011111,B00011111,B11111111,B11111111,B11000111,B11100011,B11110001,B11110000,
B00011111,B00001111,B11111111,B11111111,B11000111,B11100011,B11110001,B11110000,
B00011111,B00000000,B00000000,B00000111,B11000111,B11100011,B11110001,B11100000,
B00001111,B00000000,B00000000,B00000111,B11000111,B11100011,B11110001,B11100000,
B00001111,B00000000,B00000000,B00000111,B11000111,B11100011,B11110001,B11000000,
B00000111,B00001111,B11111111,B11111111,B11000111,B11100011,B11110001,B11000000,
B00000011,B00011111,B11111111,B11111111,B11000111,B11100011,B11110001,B10000000,
B00000011,B00011111,B11111111,B11111111,B11000111,B11100011,B11110001,B00000000,
B00000001,B00011111,B11111111,B11111111,B11000111,B11100011,B11110000,B00000000,
B00000000,B00011111,B11111111,B11111111,B11000111,B11100011,B11110000,B00000000,
B00000000,B00001111,B11111111,B11111111,B11000011,B11000001,B11100000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000111,B11000000,B00000000,B00000000,B00000000,
B00000000,B00000111,B11111111,B11111111,B11111111,B11111111,B11000000,B00000000,
B00000000,B00000011,B11111111,B11111111,B11111111,B11111111,B10000000,B00000000,
B00000000,B00000001,B11111111,B11111111,B11111111,B11111110,B00000000,B00000000,
B00000000,B00000000,B01111111,B11111111,B11111111,B11111100,B00000000,B00000000,
B00000000,B00000000,B00011111,B11111111,B11111111,B11110000,B00000000,B00000000,
B00000000,B00000000,B00000111,B11111111,B11111111,B10000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B01111111,B11111000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000
};

View File

@@ -37,7 +37,7 @@
*/
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#define CONFIGURATION_H_VERSION 010107
#define CONFIGURATION_H_VERSION 010109
//===========================================================================
//============================= Getting Started =============================
@@ -79,22 +79,27 @@
#define STRING_SPLASH_LINE1 SHORT_BUILD_VERSION // will be shown during bootup in line 1
#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2
//
// *** VENDORS PLEASE READ *****************************************************
//
// Marlin now allow you to have a vendor boot image to be displayed on machine
// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your
// custom boot image and then the default Marlin boot image is shown.
//
// We suggest for you to take advantage of this new feature and keep the Marlin
// boot image unmodified. For an example have a look at the bq Hephestos 2
// example configuration folder.
//
/**
* *** VENDORS PLEASE READ ***
*
* Marlin allows you to add a custom boot image for Graphical LCDs.
* With this option Marlin will first show your custom screen followed
* by the standard Marlin logo with version number and web URL.
*
* We encourage you to take advantage of this new feature and we also
* respectfully request that you retain the unmodified Marlin boot screen.
*/
// Enable to show the bitmap in Marlin/_Bootscreen.h on startup.
#define SHOW_CUSTOM_BOOTSCREEN
// Enable to show the bitmap in Marlin/_Statusscreen.h on the status screen.
//#define CUSTOM_STATUS_SCREEN_IMAGE
// @section machine
/**
* Select which serial port on the board will be used for communication with the host.
* Select the serial port on the board to use for communication with the host.
* This allows the connection of wireless adapters (for instance) to non-default port pins.
* Serial port 0 is always used by the Arduino bootloader regardless of this setting.
*
@@ -196,11 +201,11 @@
/**
* "Mixing Extruder"
* - Adds a new code, M165, to set the current mix factors.
* - Adds G-codes M163 and M164 to set and "commit" the current mix factors.
* - Extends the stepping routines to move multiple steppers in proportion to the mix.
* - Optional support for Repetier Firmware M163, M164, and virtual extruder.
* - This implementation supports only a single extruder.
* - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation
* - Optional support for Repetier Firmware's 'M164 S<index>' supporting virtual tools.
* - This implementation supports up to two mixing extruders.
* - Enable DIRECT_MIXING_IN_G1 for M165 and mixing in G1 (from Pia Taubert's reference implementation).
*/
//#define MIXING_EXTRUDER
#if ENABLED(MIXING_EXTRUDER)
@@ -232,6 +237,15 @@
// Enable this option to leave the PSU off at startup.
// Power to steppers and heaters will need to be turned on with M80.
//#define PS_DEFAULT_OFF
//#define AUTO_POWER_CONTROL // Enable automatic control of the PS_ON pin
#if ENABLED(AUTO_POWER_CONTROL)
#define AUTO_POWER_FANS // Turn on PSU if fans need power
#define AUTO_POWER_E_FANS
#define AUTO_POWER_CONTROLLERFAN
#define POWER_TIMEOUT 30
#endif
#endif
// @section temperature
@@ -245,6 +259,7 @@
*
* Temperature sensors available:
*
* -4 : thermocouple with AD8495
* -3 : thermocouple with MAX31855 (only for sensor 0)
* -2 : thermocouple with MAX6675 (only for sensor 0)
* -1 : thermocouple with AD595
@@ -253,7 +268,8 @@
* 2 : 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
* 3 : Mendel-parts thermistor (4.7k pullup)
* 4 : 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
* 5 : 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
* 5 : 100K thermistor - ATC Semitec 104GT-2/104NT-4-R025H42G (Used in ParCan & J-Head) (4.7k pullup)
* 501 : 100K Zonestar (Tronxy X3A) Thermistor
* 6 : 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
* 7 : 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
* 71 : 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
@@ -263,6 +279,7 @@
* 11 : 100k beta 3950 1% thermistor (4.7k pullup)
* 12 : 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
* 13 : 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
* 15 : 100k thermistor calibration for JGAurora A5 hotend
* 20 : the PT100 circuit found in the Ultimainboard V2.x
* 60 : 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
* 66 : 4.7M High Temperature thermistor from Dyze Design
@@ -284,7 +301,7 @@
* 998 : Dummy Table that ALWAYS reads 25°C or the temperature defined below.
* 999 : Dummy Table that ALWAYS reads 100°C or the temperature defined below.
*
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
* :{ '0': "Not used", '1':"100k / 4.7k - EPCOS", '2':"200k / 4.7k - ATC Semitec 204GT-2", '3':"Mendel-parts / 4.7k", '4':"10k !! do not use for a hotend. Bad resolution at high temp. !!", '5':"100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '501':"100K Zonestar (Tronxy X3A)", '6':"100k / 4.7k EPCOS - Not as accurate as Table 1", '7':"100k / 4.7k Honeywell 135-104LAG-J01", '8':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT", '9':"100k / 4.7k GE Sensing AL03006-58.2K-97-G1", '10':"100k / 4.7k RS 198-961", '11':"100k / 4.7k beta 3950 1%", '12':"100k / 4.7k 0603 SMD Vishay NTCS0603E3104FXT (calibrated for Makibox hot bed)", '13':"100k Hisens 3950 1% up to 300°C for hotend 'Simple ONE ' & hotend 'All In ONE'", '20':"PT100 (Ultimainboard V2.x)", '51':"100k / 1k - EPCOS", '52':"200k / 1k - ATC Semitec 204GT-2", '55':"100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '60':"100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '66':"Dyze Design 4.7M High Temperature thermistor", '70':"the 100K thermistor found in the bq Hephestos 2", '71':"100k / 4.7k Honeywell 135-104LAF-J01", '147':"Pt100 / 4.7k", '1047':"Pt1000 / 4.7k", '110':"Pt100 / 1k (non-standard)", '1010':"Pt1000 / 1k (non standard)", '-4':"Thermocouple + AD8495", '-3':"Thermocouple + MAX31855 (only for sensor 0)", '-2':"Thermocouple + MAX6675 (only for sensor 0)", '-1':"Thermocouple + AD595",'998':"Dummy 1", '999':"Dummy 2" }
*/
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
@@ -292,6 +309,7 @@
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_4 0
#define TEMP_SENSOR_BED 5
#define TEMP_SENSOR_CHAMBER 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
#define DUMMY_THERMISTOR_998_VALUE 25
@@ -341,7 +359,7 @@
#define PIDTEMP
#define BANG_MAX 255 // Limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // Limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define PID_K1 0.95 // Smoothing factor within the PID
#define PID_K1 0.95 // Smoothing factor within any PID loop
#if ENABLED(PIDTEMP)
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
@@ -355,47 +373,54 @@
// If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it
// Stock CR-10 tuned for 70C
#define DEFAULT_Kp 22.57
#define DEFAULT_Ki 1.72
#define DEFAULT_Kd 73.96
#define DEFAULT_Kp 22.57
#define DEFAULT_Ki 1.72
#define DEFAULT_Kd 73.96
// Ultimaker
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
//#define DEFAULT_Kd 114
//#define DEFAULT_Kp 22.2
//#define DEFAULT_Ki 1.08
//#define DEFAULT_Kd 114
// MakerGear
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
//#define DEFAULT_Kp 7.0
//#define DEFAULT_Ki 0.1
//#define DEFAULT_Kd 12
// Mendel Parts V9 on 12V
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
//#define DEFAULT_Kp 63.0
//#define DEFAULT_Ki 2.25
//#define DEFAULT_Kd 440
#endif // PIDTEMP
//===========================================================================
//============================= PID > Bed Temperature Control ===============
//===========================================================================
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
/**
* PID Bed Heating
*
* If this option is enabled set PID constants below.
* If this option is disabled, bang-bang will be used and BED_LIMIT_SWITCHING will enable hysteresis.
*
* The PID frequency will be the same as the extruder PWM.
* If PID_dT is the default, and correct for the hardware/configuration, that means 7.689Hz,
* which is fine for driving a square wave into a resistive load and does not significantly
* impact FET heating. This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W
* heater. If your configuration is significantly different than this and you don't understand
* the issues involved, don't use bed PID until someone else verifies that your hardware works.
*/
#define PIDTEMPBED
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
/**
* Max Bed Power
* Applies to all forms of bed control (PID, bang-bang, and bang-bang with hysteresis).
* When set to any value below 255, enables a form of PWM to the bed that acts like a divider
* so don't use it unless you are OK with PWM on your bed. (See the comment on enabling PIDTEMPBED)
*/
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
#if ENABLED(PIDTEMPBED)
@@ -403,36 +428,41 @@
//#define PID_BED_DEBUG // Sends debug data to the serial port.
//Stock CR-10 Bed Tuned for 70C
#define DEFAULT_bedKp 426.68
#define DEFAULT_bedKi 78.92
#define DEFAULT_bedKd 576.71
#define DEFAULT_bedKp 426.68
#define DEFAULT_bedKi 78.92
#define DEFAULT_bedKd 576.71
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
//#define DEFAULT_bedKp 10.00
//#define DEFAULT_bedKi .023
//#define DEFAULT_bedKd 305.4
//#define DEFAULT_bedKp 10.00
//#define DEFAULT_bedKi .023
//#define DEFAULT_bedKd 305.4
//120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
//#define DEFAULT_bedKp 97.1
//#define DEFAULT_bedKi 1.41
//#define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
// @section extruder
// This option prevents extrusion if the temperature is below EXTRUDE_MINTEMP.
// It also enables the M302 command to set the minimum extrusion temperature
// or to allow moving the extruder regardless of the hotend temperature.
// *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
/**
* Prevent extrusion if the temperature is below EXTRUDE_MINTEMP.
* Add M302 to set the minimum extrusion temperature and/or turn
* cold extrusion prevention on and off.
*
* *** IT IS HIGHLY RECOMMENDED TO LEAVE THIS OPTION ENABLED! ***
*/
#define PREVENT_COLD_EXTRUSION
#define EXTRUDE_MINTEMP 170
// This option prevents a single extrusion longer than EXTRUDE_MAXLENGTH.
// Note that for Bowden Extruders a too-small value here may prevent loading.
/**
* Prevent a single extrusion longer than EXTRUDE_MAXLENGTH.
* Note: For Bowden Extruders make this large enough to allow load/unload.
*/
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MAXLENGTH 1000
@@ -487,11 +517,10 @@
//#define USE_YMAX_PLUG
//#define USE_ZMAX_PLUG
// coarse Endstop Settings
//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
// Enable pullup for all endstops to prevent a floating state
//#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
@@ -510,10 +539,53 @@
#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop.
#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the probe.
/**
* Stepper Drivers
*
* These settings allow Marlin to tune stepper driver timing and enable advanced options for
* stepper drivers that support them. You may also override timing options in Configuration_adv.h.
*
* A4988 is assumed for unspecified drivers.
*
* Options: A4988, DRV8825, LV8729, L6470, TB6560, TB6600, TMC2100,
* TMC2130, TMC2130_STANDALONE, TMC2208, TMC2208_STANDALONE,
* TMC26X, TMC26X_STANDALONE, TMC2660, TMC2660_STANDALONE,
* TMC5130, TMC5130_STANDALONE
* :['A4988', 'DRV8825', 'LV8729', 'L6470', 'TB6560', 'TB6600', 'TMC2100', 'TMC2130', 'TMC2130_STANDALONE', 'TMC2208', 'TMC2208_STANDALONE', 'TMC26X', 'TMC26X_STANDALONE', 'TMC2660', 'TMC2660_STANDALONE', 'TMC5130', 'TMC5130_STANDALONE']
*/
//#define X_DRIVER_TYPE A4988
//#define Y_DRIVER_TYPE A4988
//#define Z_DRIVER_TYPE A4988
//#define X2_DRIVER_TYPE A4988
//#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988
//#define E3_DRIVER_TYPE A4988
//#define E4_DRIVER_TYPE A4988
// Enable this feature if all enabled endstop pins are interrupt-capable.
// This will remove the need to poll the interrupt pins, saving many CPU cycles.
//#define ENDSTOP_INTERRUPTS_FEATURE
/**
* Endstop Noise Filter
*
* Enable this option if endstops falsely trigger due to noise.
* NOTE: Enabling this feature means adds an error of +/-0.2mm, so homing
* will end up at a slightly different position on each G28. This will also
* reduce accuracy of some bed probes.
* For mechanical switches, the better approach to reduce noise is to install
* a 100 nanofarads ceramic capacitor in parallel with the switch, making it
* essentially noise-proof without sacrificing accuracy.
* This option also increases MCU load when endstops or the probe are enabled.
* So this is not recommended. USE AT YOUR OWN RISK.
* (This feature is not required for common micro-switches mounted on PCBs
* based on the Makerbot design, since they already include the 100nF capacitor.)
*/
//#define ENDSTOP_NOISE_FILTER
//=============================================================================
//============================== Movement Settings ============================
//=============================================================================
@@ -554,7 +626,7 @@
* Override with M201
* X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]]
*/
#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 5000 }
#define DEFAULT_MAX_ACCELERATION { 500, 500, 100, 5000 }
/**
* Default Acceleration (change/s) change = mm/s
@@ -581,6 +653,16 @@
#define DEFAULT_ZJERK 2.7
#define DEFAULT_EJERK 5.0
/**
* S-Curve Acceleration
*
* This option eliminates vibration during printing by fitting a Bézier
* curve to move acceleration, producing much smoother direction changes.
*
* See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained
*/
//#define S_CURVE_ACCELERATION
//===========================================================================
//============================= Z Probe Options =============================
//===========================================================================
@@ -631,6 +713,7 @@
* or (with LCD_BED_LEVELING) the LCD controller.
*/
//#define PROBE_MANUALLY
//#define MANUAL_PROBE_START_Z 0.2
/**
* A Fix-Mounted Probe either doesn't deploy or needs manual deployment.
@@ -641,7 +724,7 @@
/**
* Z Servo Probe, such as an endstop switch on a rotating arm.
*/
//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_PROBE_SERVO_NR 0 // Defaults to SERVO 0 connector.
//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles
/**
@@ -660,6 +743,9 @@
* readings with inductive probes and piezo sensors.
*/
//#define PROBING_HEATERS_OFF // Turn heaters off when probing
#if ENABLED(PROBING_HEATERS_OFF)
//#define WAIT_FOR_BED_HEATER // Wait for bed to heat back up between probes (to improve accuracy)
#endif
//#define PROBING_FANS_OFF // Turn fans off when probing
//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors
@@ -697,13 +783,16 @@
#define Y_PROBE_OFFSET_FROM_EXTRUDER 10 // Y offset: -front +behind [the nozzle]
#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle]
// Certain types of probes need to stay away from edges
#define MIN_PROBE_EDGE 10
// X and Y axis travel speed (mm/m) between probes
#define XY_PROBE_SPEED 8000
// Speed for the first approach when double-probing (MULTIPLE_PROBING == 2)
// Feedrate (mm/m) for the first approach when double-probing (MULTIPLE_PROBING == 2)
#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z
// Speed for the "accurate" probe of each point
// Feedrate (mm/m) for the "accurate" probe of each point
#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2)
// The number of probes to perform at each point.
@@ -727,6 +816,10 @@
*/
#define Z_CLEARANCE_DEPLOY_PROBE 10 // Z Clearance for Deploy/Stow
#define Z_CLEARANCE_BETWEEN_PROBES 10 // Z Clearance between probe points
#define Z_CLEARANCE_MULTI_PROBE 5 // Z Clearance between multiple probes
//#define Z_AFTER_PROBING 10 // Z position after probing is done
#define Z_PROBE_LOW_POINT -2 // Farthest distance below the trigger-point to go before stopping
// For M851 give a range for adjusting the Z probe offset
#define Z_PROBE_OFFSET_RANGE_MIN -20
@@ -762,9 +855,6 @@
#define INVERT_Y_DIR true
#define INVERT_Z_DIR false
// Enable this option for Toshiba stepper drivers
//#define CONFIG_STEPPERS_TOSHIBA
// @section extruder
// For direct drive extruder v9 set to true, for geared extruder set to false.
@@ -778,6 +868,8 @@
//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed
//#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off.
//#define Z_HOMING_HEIGHT 5 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ...
// Be sure you have this distance over your Z_MAX_POS in case.
@@ -810,7 +902,7 @@
* - Use 'M211' to set software endstops on/off or report current state
*/
// Min software endstops curtail movement below minimum coordinate bounds
// Min software endstops constrain movement within minimum coordinate bounds
#define MIN_SOFTWARE_ENDSTOPS
#if ENABLED(MIN_SOFTWARE_ENDSTOPS)
#define MIN_SOFTWARE_ENDSTOP_X
@@ -818,7 +910,7 @@
#define MIN_SOFTWARE_ENDSTOP_Z
#endif
// Max software endstops curtail movement above maximum coordinate bounds
// Max software endstops constrain movement within maximum coordinate bounds
#define MAX_SOFTWARE_ENDSTOPS
#if ENABLED(MAX_SOFTWARE_ENDSTOPS)
#define MAX_SOFTWARE_ENDSTOP_X
@@ -826,18 +918,23 @@
#define MAX_SOFTWARE_ENDSTOP_Z
#endif
#if ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)
//#define SOFT_ENDSTOPS_MENU_ITEM // Enable/Disable software endstops from the LCD
#endif
/**
* Filament Runout Sensor
* A mechanical or opto endstop is used to check for the presence of filament.
* Filament Runout Sensors
* Mechanical or opto endstops are used to check for the presence of filament.
*
* RAMPS-based boards use SERVO3_PIN.
* For other boards you may need to define FIL_RUNOUT_PIN.
* By default the firmware assumes HIGH = has filament, LOW = ran out
* RAMPS-based boards use SERVO3_PIN for the first runout sensor.
* For other boards you may need to define FIL_RUNOUT_PIN, FIL_RUNOUT2_PIN, etc.
* By default the firmware assumes HIGH=FILAMENT PRESENT.
*/
//#define FILAMENT_RUNOUT_SENSOR
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define NUM_RUNOUT_SENSORS 1 // Number of sensors, up to one per extruder. Define a FIL_RUNOUT#_PIN for each.
#define FIL_RUNOUT_INVERTING false // set to true to invert the logic of the sensor.
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FIL_RUNOUT_PULLUP // Use internal pullup for filament runout pins.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
@@ -885,6 +982,12 @@
//#define AUTO_BED_LEVELING_UBL
//#define MESH_BED_LEVELING
/**
* Normally G28 leaves leveling disabled on completion. Enable
* this option to have G28 restore the prior leveling state.
*/
//#define RESTORE_LEVELING_AFTER_G28
/**
* Enable detailed logging of G28, G29, M48, etc.
* Turn on with the command 'M111 S32'.
@@ -907,12 +1010,12 @@
/**
* Enable the G26 Mesh Validation Pattern tool.
*/
//#define G26_MESH_VALIDATION // Enable G26 mesh validation
//#define G26_MESH_VALIDATION
#if ENABLED(G26_MESH_VALIDATION)
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_NOZZLE_SIZE 0.4 // (mm) Diameter of primary nozzle.
#define MESH_TEST_LAYER_HEIGHT 0.2 // (mm) Default layer height for the G26 Mesh Validation Tool.
#define MESH_TEST_HOTEND_TEMP 205.0 // (°C) Default nozzle temperature for the G26 Mesh Validation Tool.
#define MESH_TEST_BED_TEMP 60.0 // (°C) Default bed temperature for the G26 Mesh Validation Tool.
#endif
#endif
@@ -924,13 +1027,10 @@
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
// Set the boundaries for probing (where the probe can reach).
#define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170
#define FRONT_PROBE_BED_POSITION 20
#define BACK_PROBE_BED_POSITION 170
// The Z probe minimum outer margin (to validate G29 parameters).
#define MIN_PROBE_EDGE 10
//#define LEFT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define RIGHT_PROBE_BED_POSITION (X_BED_SIZE - MIN_PROBE_EDGE)
//#define FRONT_PROBE_BED_POSITION MIN_PROBE_EDGE
//#define BACK_PROBE_BED_POSITION (Y_BED_SIZE - MIN_PROBE_EDGE)
// Probe along the Y axis, advancing X after each column
//#define PROBE_Y_FIRST
@@ -953,17 +1053,6 @@
#endif
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
// 3 arbitrary points to probe.
// A simple cross-product is used to estimate the plane of the bed.
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#elif ENABLED(AUTO_BED_LEVELING_UBL)
//===========================================================================
@@ -972,27 +1061,23 @@
//#define MESH_EDIT_GFX_OVERLAY // Display a graphics overlay while editing the mesh
#define MESH_INSET 1 // Mesh inset margin on print area
#define MESH_INSET 1 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
#define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh
#define UBL_PROBE_PT_1_Y 180
#define UBL_PROBE_PT_2_X 39
#define UBL_PROBE_PT_2_Y 20
#define UBL_PROBE_PT_3_X 180
#define UBL_PROBE_PT_3_Y 20
#define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle
#define UBL_SAVE_ACTIVE_ON_M500 // Save the currently active mesh in the current slot on M500
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
//=================================== Mesh ==================================
//===========================================================================
#define MESH_INSET 10 // Mesh inset margin on print area
#define MESH_INSET 10 // Set Mesh bounds as an inset region of the bed
#define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited.
#define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X
@@ -1001,8 +1086,21 @@
#endif // BED_LEVELING
/**
* Use the LCD controller for bed leveling
* Requires MESH_BED_LEVELING or PROBE_MANUALLY
* Points to probe for all 3-point Leveling procedures.
* Override if the automatically selected points are inadequate.
*/
#if ENABLED(AUTO_BED_LEVELING_3POINT) || ENABLED(AUTO_BED_LEVELING_UBL)
//#define PROBE_PT_1_X 15
//#define PROBE_PT_1_Y 180
//#define PROBE_PT_2_X 15
//#define PROBE_PT_2_Y 20
//#define PROBE_PT_3_X 170
//#define PROBE_PT_3_Y 20
#endif
/**
* Add a bed leveling sub-menu for ABL or MBL.
* Include a guided procedure if manual probing is enabled.
*/
//#define LCD_BED_LEVELING
@@ -1014,6 +1112,11 @@
// Add a menu item to move between bed corners for manual bed adjustment
#define LEVEL_BED_CORNERS
#if ENABLED(LEVEL_BED_CORNERS)
#define LEVEL_CORNERS_INSET 30 // (mm) An inset for corner leveling
//#define LEVEL_CENTER_TOO // Move to the center after the last corner
#endif
/**
* Commands to execute at the end of G29 probing.
* Useful to retract or move the Z probe out of the way.
@@ -1287,11 +1390,11 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, fr_utf8, gl,
* hr, it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8,
* tr, uk, zh_CN, zh_TW, test
* en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, es_utf8,
* eu, fi, fr, fr_utf8, gl, hr, it, kana, kana_utf8, nl, pl, pt,
* pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, tr, uk, zh_CN, zh_TW, test
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'es_utf8':'Spanish (UTF8)', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'fr_utf8':'French (UTF8)', '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', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', 'test':'TEST' }
*/
#define LCD_LANGUAGE en
@@ -1319,19 +1422,6 @@
*/
#define DISPLAY_CHARSET_HD44780 JAPANESE
/**
* 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
*
@@ -1358,19 +1448,28 @@
*/
//#define SD_CHECK_AND_RETRY
/**
* LCD Menu Items
*
* Disable all menus and only display the Status Screen, or
* just remove some extraneous menu items to recover space.
*/
//#define NO_LCD_MENUS
//#define SLIM_LCD_MENUS
//
// ENCODER SETTINGS
//
// This option overrides the default number of encoder pulses needed to
// produce one step. Should be increased for high-resolution encoders.
//
#define ENCODER_PULSES_PER_STEP 4
//#define ENCODER_PULSES_PER_STEP 4
//
// Use this option to override the number of step signals required to
// move between next/prev menu items.
//
#define ENCODER_STEPS_PER_MENU_ITEM 1
//#define ENCODER_STEPS_PER_MENU_ITEM 1
/**
* Encoder Direction Options
@@ -1422,12 +1521,18 @@
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
//#define LCD_FEEDBACK_FREQUENCY_HZ 5000
//=============================================================================
//======================== LCD / Controller Selection =========================
//======================== (Character-based LCDs) =========================
//=============================================================================
//
// CONTROLLER TYPE: Standard
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Marlin supports a wide variety of controllers.
// Enable one of the following options to specify your controller.
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// ULTIMAKER Controller.
@@ -1445,40 +1550,6 @@
//
//#define PANEL_ONE
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// RepRapDiscount Smart Controller.
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//
// Note: Usually sold with a white PCB.
//
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
//
// GADGETS3D G3D LCD/SD Controller
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
@@ -1487,28 +1558,6 @@
//
//#define G3D_PANEL
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0
//
// RigidBot Panel V1.0
// http://www.inventapart.com/
@@ -1516,33 +1565,28 @@
//#define RIGIDBOT_PANEL
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define BQ_LCD_SMART_CONTROLLER
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// ANET and Tronxy Controller supported displays.
// ANET and Tronxy 20x4 Controller
//
//#define ZONESTAR_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin.
// This LCD is known to be susceptible to electrical interference
// which scrambles the display. Pressing any button clears it up.
// This is a LCD2004 display with 5 analog buttons.
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// Generic 16x2, 16x4, 20x2, or 20x4 character-based LCD.
//
//#define ULTRA_LCD
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//=============================================================================
//======================== LCD / Controller Selection =========================
//===================== (I2C and Shift-Register LCDs) =====================
//=============================================================================
//
// CONTROLLER TYPE: I2C
@@ -1558,12 +1602,13 @@
//#define RA_CONTROL_PANEL
//
// Sainsmart YW Robot (LCM1602) LCD Display
// Sainsmart (YwRobot) LCD Displays
//
// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library
// These require F.Malpartida's LiquidCrystal_I2C library
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home
//
//#define LCD_I2C_SAINSMART_YWROBOT
//#define LCD_SAINSMART_I2C_1602
//#define LCD_SAINSMART_I2C_2004
//
// Generic LCM1602 LCD adapter
@@ -1588,6 +1633,83 @@
//
//#define LCD_I2C_VIKI
//
// CONTROLLER TYPE: Shift register panels
//
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//=============================================================================
//======================= LCD / Controller Selection =======================
//========================= (Graphical LCDs) ========================
//=============================================================================
//
// CONTROLLER TYPE: Graphical 128x64 (DOGM)
//
// IMPORTANT: The U8glib library is required for Graphical Display!
// https://github.com/olikraus/U8glib_Arduino
//
//
// RepRapDiscount FULL GRAPHIC Smart Controller
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
//
// ReprapWorld Graphical LCD
// https://reprapworld.com/?products_details&products_id/1218
//
//#define REPRAPWORLD_GRAPHICAL_LCD
//
// Activate one of these if you have a Panucatt Devices
// Viki 2.0 or mini Viki with Graphic LCD
// http://panucatt.com
//
//#define VIKI2
//#define miniVIKI
//
// MakerLab Mini Panel with graphic
// controller and SD support - http://reprap.org/wiki/Mini_panel
//
//#define MINIPANEL
//
// MaKr3d Makr-Panel with graphic controller and SD support.
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//
//#define MAKRPANEL
//
// Adafruit ST7565 Full Graphic Controller.
// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/
//
//#define ELB_FULL_GRAPHIC_CONTROLLER
//
// BQ LCD Smart Controller shipped by
// default with the BQ Hephestos 2 and Witbox 2.
//
//#define BQ_LCD_SMART_CONTROLLER
//
// Cartesio UI
// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface
//
//#define CARTESIO_UI
//
// LCD for Melzi Card with Graphical LCD
//
//#define LCD_FOR_MELZI
//
// SSD1306 OLED full graphics generic display
//
@@ -1603,24 +1725,16 @@
#endif
//
// CONTROLLER TYPE: Shift register panels
// Original Ulticontroller from Ultimaker 2 printer with SSD1309 I2C display and encoder
// https://github.com/Ultimaker/Ultimaker2/tree/master/1249_Ulticontroller_Board_(x1)
//
// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH
// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD
//
//#define SAV_3DLCD
//#define ULTI_CONTROLLER
//
// TinyBoy2 128x64 OLED / Encoder Panel
//
//#define OLED_PANEL_TINYBOY2
//
// Makeboard 3D Printer Parts 3D Printer Mini Display 1602 Mini Controller
// https://www.aliexpress.com/item/Micromake-Makeboard-3D-Printer-Parts-3D-Printer-Mini-Display-1602-Mini-Controller-Compatible-with-Ramps-1/32765887917.html
//
//#define MAKEBOARD_MINI_2_LINE_DISPLAY_1602
//
// MKS MINI12864 with graphic controller and SD support
// http://reprap.org/wiki/MKS_MINI_12864
@@ -1636,6 +1750,13 @@
//
#define CR10_STOCKDISPLAY
//
// ANET and Tronxy Graphical Controller
//
//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6
// A clone of the RepRapDiscount full graphics display but with
// different pins/wiring (see pins_ANET_10.h).
//
// MKS OLED 1.3" 128 × 64 FULL GRAPHICS CONTROLLER
// http://reprap.org/wiki/MKS_12864OLED
@@ -1645,11 +1766,40 @@
//#define MKS_12864OLED // Uses the SH1106 controller (default)
//#define MKS_12864OLED_SSD1306 // Uses the SSD1306 controller
//
// Silvergate GLCD controller
// http://github.com/android444/Silvergate
//
//#define SILVER_GATE_GLCD_CONTROLLER
//=============================================================================
//============================ Other Controllers ============================
//=============================================================================
//
// CONTROLLER TYPE: Standalone / Serial
//
//
// LCD for Malyan M200 printers.
// This requires SDSUPPORT to be enabled
//
//#define MALYAN_LCD
//
// CONTROLLER TYPE: Keypad / Add-on
//
//
// RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//
// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key
// is pressed, a value of 10.0 means 10mm per click.
//
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0
//=============================================================================
//=============================== Extra Features ==============================
//=============================================================================
@@ -1709,7 +1859,7 @@
* For Neopixel LED an overall brightness parameter is also available.
*
* *** CAUTION ***
* LED Strips require a MOFSET Chip between PWM lines and LEDs,
* LED Strips require a MOSFET Chip between PWM lines and LEDs,
* as the Arduino cannot handle the current the LEDs will require.
* Failure to follow this precaution can destroy your Arduino!
* NOTE: A separate 5V power supply is required! The Neopixel LED needs
@@ -1774,9 +1924,7 @@
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
// Servo deactivation
//
// With this option servos are powered only during movement, then turned off to prevent jitter.
// Only power servos during movement, otherwise leave off to prevent jitter
//#define DEACTIVATE_SERVOS_AFTER_MOVE
#endif // CONFIGURATION_H

View File

@@ -32,7 +32,7 @@
*/
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H_VERSION 010107
#define CONFIGURATION_ADV_H_VERSION 010109
// @section temperature
@@ -40,6 +40,17 @@
//=============================Thermal Settings ============================
//===========================================================================
//
// Hephestos 2 24V heated bed upgrade kit.
// https://store.bq.com/en/heated-bed-kit-hephestos2
//
//#define HEPHESTOS2_HEATED_BED_KIT
#if ENABLED(HEPHESTOS2_HEATED_BED_KIT)
#undef TEMP_SENSOR_BED
#define TEMP_SENSOR_BED 70
#define HEATER_BED_INVERTING true
#endif
#if DISABLED(PIDTEMPBED)
#define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control
#if ENABLED(BED_LIMIT_SWITCHING)
@@ -171,10 +182,12 @@
// @section temperature
//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Calibration for AD595 / AD8495 sensor to adjust temperature measurements.
// The final temperature is calculated as (measuredTemp * GAIN) + OFFSET.
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
#define TEMP_SENSOR_AD8495_OFFSET 0.0
#define TEMP_SENSOR_AD8495_GAIN 1.0
/**
* Controller Fan
@@ -185,7 +198,7 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
#define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled
#define CONTROLLERFAN_SPEED 255 // 255 == full speed
#endif
@@ -195,10 +208,20 @@
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
//#define FAN_KICKSTART_TIME 100
// This defines the minimal speed for the main fan, run in PWM mode
// to enable uncomment and set minimal PWM speed for reliable running (1-255)
// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM
/**
* PWM Fan Scaling
*
* Define the min/max speeds for PWM fans (as set with M106).
*
* With these options the M106 0-255 value range is scaled to a subset
* to ensure that the fan has enough power to spin, or to run lower
* current fans with higher current. (e.g., 5V/12V fans with 12V/24V)
* Value 0 always turns off the fan.
*
* Define one or both of these to override the default 0-255 range.
*/
//#define FAN_MIN_PWM 50
//#define FAN_MAX_PWM 128
// @section extruder
@@ -219,6 +242,7 @@
#define E2_AUTO_FAN_PIN -1
#define E3_AUTO_FAN_PIN -1
#define E4_AUTO_FAN_PIN -1
#define CHAMBER_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@@ -243,6 +267,10 @@
#define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin)
//#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu
//#define CASE_LIGHT_USE_NEOPIXEL // Use Neopixel LED as case light, requires NEOPIXEL_LED.
#if ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASE_LIGHT_NEOPIXEL_COLOR { 255, 255, 255, 255 } // { Red, Green, Blue, White }
#endif
#endif
//===========================================================================
@@ -303,15 +331,20 @@
#endif
#endif
// Enable this for dual x-carriage printers.
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug.
/**
* Dual X Carriage
*
* This setup has two X carriages that can move independently, each with its own hotend.
* The carriages can be used to print an object with two colors or materials, or in
* "duplication mode" it can print two identical or X-mirrored objects simultaneously.
* The inactive carriage is parked automatically to prevent oozing.
* X1 is the left carriage, X2 the right. They park and home at opposite ends of the X axis.
* By default the X2 stepper is assigned to the first unused E plug on the board.
*/
//#define DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
// Configuration for second X-carriage
// Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop;
// the second x-carriage always homes to the maximum endstop.
#define X1_MIN_POS X_MIN_POS // set minimum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X1_MAX_POS X_BED_SIZE // set maximum to ensure first x-carriage doesn't hit the parked second X-carriage
#define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
#define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed
#define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position
@@ -358,6 +391,9 @@
// When G28 is called, this option will make Y home before X
//#define HOME_Y_BEFORE_X
// Enable this if X or Y can't home without homing the other axis first.
//#define CODEPENDENT_XY_HOMING
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@@ -410,8 +446,24 @@
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec)
//
// Use Junction Deviation instead of traditional Jerk Limiting
//
//#define JUNCTION_DEVIATION
#if ENABLED(JUNCTION_DEVIATION)
#define JUNCTION_DEVIATION_MM 0.02 // (mm) Distance from real junction edge
#endif
/**
* Adaptive Step Smoothing increases the resolution of multi-axis moves, particularly at step frequencies
* below 1kHz (for AVR) or 10kHz (for ARM), where aliasing between axes in multi-axis moves causes audible
* vibration and surface artifacts. The algorithm adapts to provide the best possible step smoothing at the
* lowest stepping frequencies.
*/
//#define ADAPTIVE_STEP_SMOOTHING
// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU.
#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16]
#define MICROSTEP_MODES { 16, 16, 16, 16, 16 } // [1,2,4,8,16]
/**
* @section stepper motor current
@@ -454,7 +506,8 @@
//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster
#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8
// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
// Actual motor currents in Amps. The number of entries must match DIGIPOT_I2C_NUM_CHANNELS.
// These correspond to the physical drivers, so be mindful if the order is changed.
#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO
//===========================================================================
@@ -482,6 +535,20 @@
// The timeout (in ms) to return to the status screen from sub-menus
//#define LCD_TIMEOUT_TO_STATUS 15000
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
#if ENABLED(SDSUPPORT) || ENABLED(LCD_SET_PROGRESS_MANUALLY)
//#define LCD_PROGRESS_BAR // Show a progress bar on HD44780 LCDs for SD printing
#if ENABLED(LCD_PROGRESS_BAR)
#define PROGRESS_BAR_BAR_TIME 2000 // (ms) Amount of time to show the bar
#define PROGRESS_BAR_MSG_TIME 3000 // (ms) Amount of time to show the status message
#define PROGRESS_MSG_EXPIRE 0 // (ms) Amount of time to retain the status message (0=forever)
//#define PROGRESS_MSG_ONCE // Show the message for MSG_TIME then clear it
//#define LCD_PROGRESS_BAR_TEST // Add a menu item to test the progress bar
#endif
#endif // SDSUPPORT || LCD_SET_PROGRESS_MANUALLY
/**
* LED Control Menu
* Enable this feature to add LED Control to the LCD menu
@@ -518,6 +585,20 @@
// Add an option in the menu to run all auto#.g files
//#define MENU_ADDAUTOSTART
/**
* Continue after Power-Loss (Creality3D)
*
* Store the current state to the SD Card at the start of each layer
* during SD printing. If the recovery file is found at boot time, present
* an option on the LCD screen to continue the print from the last-known
* point in the file.
*/
//#define POWER_LOSS_RECOVERY
#if ENABLED(POWER_LOSS_RECOVERY)
//#define POWER_LOSS_PIN 44 // Pin to detect power loss
//#define POWER_LOSS_STATE HIGH // State of pin indicating power loss
#endif
/**
* Sort SD file listings in alphabetical order.
*
@@ -556,25 +637,6 @@
// Note: Only affects SCROLL_LONG_FILENAMES with SDSORT_CACHE_NAMES but not SDSORT_DYNAMIC_RAM.
#endif
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#if ENABLED(LCD_PROGRESS_BAR)
// Amount of time (ms) to show the bar
#define PROGRESS_BAR_BAR_TIME 2000
// Amount of time (ms) to show the status message
#define PROGRESS_BAR_MSG_TIME 3000
// Amount of time (ms) to retain the status message (0=forever)
#define PROGRESS_MSG_EXPIRE 0
// Enable this to show messages for MSG_TIME then hide them
//#define PROGRESS_MSG_ONCE
// Add a menu item to test the progress bar:
//#define LCD_PROGRESS_BAR_TEST
#endif
// Add an 'M73' G-code to set the current percentage
//#define LCD_SET_PROGRESS_MANUALLY
// This allows hosts to request long names for files and folders with M33
//#define LONG_FILENAME_HOST_SUPPORT
@@ -595,6 +657,11 @@
*/
//#define SD_REPRINT_LAST_SELECTED_FILE
/**
* Auto-report SdCard status with M27 S<seconds>
*/
//#define AUTO_REPORT_SD_STATUS
#endif // SDSUPPORT
/**
@@ -610,6 +677,9 @@
* printing performance versus fast display updates.
*/
#if ENABLED(DOGLCD)
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on the Info Screen
#define XYZ_HOLLOW_FRAME
@@ -631,6 +701,25 @@
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#if ENABLED(U8GLIB_ST7920)
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
* Enable LIGHTWEIGHT_UI to use this special display mode.
*
* Since LIGHTWEIGHT_UI has limited space, the position and status
* message occupy the same line. Set STATUS_EXPIRE_SECONDS to the
* length of time to display the status message before clearing.
*
* Set STATUS_EXPIRE_SECONDS to zero to never clear the status.
* This will prevent position updates from being displayed.
*/
//#define LIGHTWEIGHT_UI
#if ENABLED(LIGHTWEIGHT_UI)
#define STATUS_EXPIRE_SECONDS 20
#endif
#endif
#endif // DOGLCD
// @section safety
@@ -670,53 +759,29 @@
// @section extruder
/**
* Implementation of linear pressure control
* Linear Pressure Control v1.5
*
* Assumption: advance = k * (delta velocity)
* Assumption: advance [steps] = k * (delta velocity [steps/s])
* K=0 means advance disabled.
* See Marlin documentation for calibration instructions.
*
* NOTE: K values for LIN_ADVANCE 1.5 differ from earlier versions!
*
* Set K around 0.22 for 3mm PLA Direct Drive with ~6.5cm between the drive gear and heatbreak.
* Larger K values will be needed for flexible filament and greater distances.
* If this algorithm produces a higher speed offset than the extruder can handle (compared to E jerk)
* print acceleration will be reduced during the affected moves to keep within the limit.
*
* See http://marlinfw.org/docs/features/lin_advance.html for full instructions.
* Mention @Sebastianv650 on GitHub to alert the author of any issues.
*/
//#define LIN_ADVANCE
#if ENABLED(LIN_ADVANCE)
#define LIN_ADVANCE_K 75
/**
* Some Slicers produce Gcode with randomly jumping extrusion widths occasionally.
* For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width.
* While this is harmless for normal printing (the fluid nature of the filament will
* close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption.
*
* For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio
* to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures
* if the slicer is using variable widths or layer heights within one print!
*
* This option sets the default E:D ratio at startup. Use `M900` to override this value.
*
* Example: `M900 W0.4 H0.2 D1.75`, where:
* - W is the extrusion width in mm
* - H is the layer height in mm
* - D is the filament diameter in mm
*
* Example: `M900 R0.0458` to set the ratio directly.
*
* Set to 0 to auto-detect the ratio based on given Gcode G1 print moves.
*
* Slic3r (including Průša Control) produces Gcode compatible with the automatic mode.
* Cura (as of this writing) may produce Gcode incompatible with the automatic mode.
*/
#define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI)
// Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135
#define LIN_ADVANCE_K 0.22 // Unit: mm compression per 1mm/s extruder speed
//#define LA_DEBUG // If enabled, this will generate debug information output over USB.
#endif
// @section leveling
#if ENABLED(DELTA) && !defined(DELTA_PROBEABLE_RADIUS)
#define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS
#elif IS_SCARA && !defined(SCARA_PRINTABLE_RADIUS)
#define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2)
#endif
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL)
// Override the mesh area if the automatic (max) area is too large
//#define MESH_MIN_X MESH_INSET
@@ -751,9 +816,46 @@
// Moves (or segments) with fewer steps than this will be joined with the next move
#define MIN_STEPS_PER_SEGMENT 6
// The minimum pulse width (in µs) for stepping a stepper.
// Set this if you find stepping unreliable, or if using a very fast CPU.
#define MINIMUM_STEPPER_PULSE 0 // (µs) The smallest stepper pulse allowed
/**
* Minimum delay after setting the stepper DIR (in ns)
* 0 : No delay (Expect at least 10µS since one Stepper ISR must transpire)
* 20 : Minimum for TMC2xxx drivers
* 200 : Minimum for A4988 drivers
* 500 : Minimum for LV8729 drivers (guess, no info in datasheet)
* 650 : Minimum for DRV8825 drivers
* 1500 : Minimum for TB6600 drivers (guess, no info in datasheet)
* 15000 : Minimum for TB6560 drivers (guess, no info in datasheet)
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_DIR_DELAY 650
/**
* Minimum stepper driver pulse width (in µs)
* 0 : Smallest possible width the MCU can produce, compatible with TMC2xxx drivers
* 1 : Minimum for A4988 stepper drivers
* 1 : Minimum for LV8729 stepper drivers
* 2 : Minimum for DRV8825 stepper drivers
* 3 : Minimum for TB6600 stepper drivers
* 30 : Minimum for TB6560 stepper drivers
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MINIMUM_STEPPER_PULSE 2
/**
* Maximum stepping rate (in Hz) the stepper driver allows
* If undefined, defaults to 1MHz / (2 * MINIMUM_STEPPER_PULSE)
* 500000 : Maximum for A4988 stepper driver
* 400000 : Maximum for TMC2xxx stepper drivers
* 250000 : Maximum for DRV8825 stepper driver
* 150000 : Maximum for TB6600 stepper driver
* 130000 : Maximum for LV8729 stepper driver
* 15000 : Maximum for TB6560 stepper driver
*
* Override the default value based on the driver type set in Configuration.h.
*/
//#define MAXIMUM_STEPPER_RATE 250000
// @section temperature
@@ -878,53 +980,55 @@
*/
#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s
#define PAUSE_PARK_RETRACT_LENGTH 4 // 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 420 // Unload filament length from hotend in mm
// Longer length for bowden printers to unload filament from whole bowden tube,
// shorter length for printers without bowden to unload filament from extruder only,
// 0 to disable unloading for manual unloading
#define FILAMENT_CHANGE_LOAD_FEEDRATE 8 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast
#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 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 PAUSE_PARK_NOZZLE_TIMEOUT 120 // Turn off nozzle if user doesn't change filament within this time limit in seconds
#define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 3 // Number of alert beeps before printer goes quiet
#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 HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
#define PAUSE_PARK_RETRACT_FEEDRATE 60 // (mm/s) Initial retract feedrate.
#define PAUSE_PARK_RETRACT_LENGTH 4 // (mm) Initial retract.
// This short retract is done immediately, before parking the nozzle.
#define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // (mm/s) Unload filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_UNLOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_UNLOAD_LENGTH 420 // (mm) The length of filament for a complete unload.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
// Set to 0 for manual unloading.
#define FILAMENT_CHANGE_SLOW_LOAD_FEEDRATE 6 // (mm/s) Slow move when starting load.
#define FILAMENT_CHANGE_SLOW_LOAD_LENGTH 0 // (mm) Slow length, to allow time to insert material.
// 0 to disable start loading and skip to fast load only
#define FILAMENT_CHANGE_FAST_LOAD_FEEDRATE 8 // (mm/s) Load filament feedrate. This can be pretty fast.
#define FILAMENT_CHANGE_FAST_LOAD_ACCEL 25 // (mm/s^2) Lower acceleration may allow a faster feedrate.
#define FILAMENT_CHANGE_FAST_LOAD_LENGTH 0 // (mm) Load length of filament, from extruder gear to nozzle.
// For Bowden, the full length of the tube and nozzle.
// For direct drive, the full length of the nozzle.
//#define ADVANCED_PAUSE_CONTINUOUS_PURGE // Purge continuously up to the purge length until interrupted.
#define ADVANCED_PAUSE_PURGE_FEEDRATE 3 // (mm/s) Extrude feedrate (after loading). Should be slower than load feedrate.
#define ADVANCED_PAUSE_PURGE_LENGTH 50 // (mm) Length to extrude after loading.
// Set to 0 for manual extrusion.
// Filament can be extruded repeatedly from the Filament Change menu
// until extrusion is consistent, and to purge old filament.
// Filament Unload does a Retract, Delay, and Purge first:
#define FILAMENT_UNLOAD_RETRACT_LENGTH 13 // (mm) Unload initial retract length.
#define FILAMENT_UNLOAD_DELAY 5000 // (ms) Delay for the filament to cool after retract.
#define FILAMENT_UNLOAD_PURGE_LENGTH 8 // (mm) An unretract is done, then this length is purged.
#define PAUSE_PARK_NOZZLE_TIMEOUT 120 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 6 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change
//#define FILAMENT_LOAD_UNLOAD_GCODES // Add M701/M702 Load/Unload G-codes, plus Load/Unload in the LCD Prepare menu.
//#define FILAMENT_UNLOAD_ALL_EXTRUDERS // Allow M702 to unload all extruders above a minimum target temp (as set by M302)
#endif
// @section tmc
/**
* Enable this section if you have TMC26X motor drivers.
* You will need to import the TMC26XStepper library into the Arduino IDE for this
* (https://github.com/trinamic/TMC26XStepper.git)
* TMC26X Stepper Driver options
*
* The TMC26XStepper library is required for this stepper driver.
* https://github.com/trinamic/TMC26XStepper
*/
//#define HAVE_TMCDRIVER
#if ENABLED(HAVE_TMCDRIVER)
//#define X_IS_TMC
//#define X2_IS_TMC
//#define Y_IS_TMC
//#define Y2_IS_TMC
//#define Z_IS_TMC
//#define Z2_IS_TMC
//#define E0_IS_TMC
//#define E1_IS_TMC
//#define E2_IS_TMC
//#define E3_IS_TMC
//#define E4_IS_TMC
#if HAS_DRIVER(TMC26X)
#define X_MAX_CURRENT 1000 // in mA
#define X_SENSE_RESISTOR 91 // in mOhms
@@ -972,62 +1076,27 @@
#endif
// @section TMC2130, TMC2208
// @section tmc_smart
/**
* Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers.
* To use TMC2130 stepper drivers in SPI mode connect your SPI pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
* You may also use software SPI if you wish to use general purpose IO pins.
*
* You'll also need the TMC2130Stepper Arduino library
* (https://github.com/teemuatlut/TMC2130Stepper).
*
* To use TMC2130 stepper drivers in SPI mode connect your SPI2130 pins to
* the hardware SPI interface on your board and define the required CS pins
* in your `pins_MYBOARD.h` file. (e.g., RAMPS 1.4 uses AUX3 pins `X_CS_PIN 53`, `Y_CS_PIN 49`, etc.).
*/
//#define HAVE_TMC2130
/**
* Enable this for SilentStepStick Trinamic TMC2208 UART-configurable stepper drivers.
* Connect #_SERIAL_TX_PIN to the driver side PDN_UART pin.
* To use TMC2208 stepper UART-configurable stepper drivers
* connect #_SERIAL_TX_PIN to the driver side PDN_UART pin with a 1K resistor.
* To use the reading capabilities, also connect #_SERIAL_RX_PIN
* to #_SERIAL_TX_PIN with a 1K resistor.
* to PDN_UART without a resistor.
* The drivers can also be used with hardware serial.
*
* You'll also need the TMC2208Stepper Arduino library
* (https://github.com/teemuatlut/TMC2208Stepper).
*/
//#define HAVE_TMC2208
#if ENABLED(HAVE_TMC2130) || ENABLED(HAVE_TMC2208)
// CHOOSE YOUR MOTORS HERE, THIS IS MANDATORY
//#define X_IS_TMC2130
//#define X2_IS_TMC2130
//#define Y_IS_TMC2130
//#define Y2_IS_TMC2130
//#define Z_IS_TMC2130
//#define Z2_IS_TMC2130
//#define E0_IS_TMC2130
//#define E1_IS_TMC2130
//#define E2_IS_TMC2130
//#define E3_IS_TMC2130
//#define E4_IS_TMC2130
//#define X_IS_TMC2208
//#define X2_IS_TMC2208
//#define Y_IS_TMC2208
//#define Y2_IS_TMC2208
//#define Z_IS_TMC2208
//#define Z2_IS_TMC2208
//#define E0_IS_TMC2208
//#define E1_IS_TMC2208
//#define E2_IS_TMC2208
//#define E3_IS_TMC2208
//#define E4_IS_TMC2208
/**
* Stepper driver settings
*/
#if HAS_TRINAMIC
#define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130
#define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current
@@ -1066,6 +1135,16 @@
#define E4_CURRENT 800
#define E4_MICROSTEPS 16
/**
* Use software SPI for TMC2130.
* The default SW SPI pins are defined the respective pins files,
* but you can override or define them here.
*/
//#define TMC_USE_SW_SPI
//#define TMC_SW_MOSI -1
//#define TMC_SW_MISO -1
//#define TMC_SW_SCK -1
/**
* Use Trinamic's ultra quiet stepping mode.
* When disabled, Marlin will use spreadCycle stepping mode.
@@ -1114,20 +1193,21 @@
/**
* Use stallGuard2 to sense an obstacle and trigger an endstop.
* You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin.
* X and Y homing will always be done in spreadCycle mode.
* X, Y, and Z homing will always be done in spreadCycle mode.
*
* X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* X/Y/Z_HOMING_SENSITIVITY is used for tuning the trigger sensitivity.
* Higher values make the system LESS sensitive.
* Lower value make the system MORE sensitive.
* Too low values can lead to false positives, while too high values will collide the axis without triggering.
* It is advised to set X/Y_HOME_BUMP_MM to 0.
* M914 X/Y to live tune the setting
* It is advised to set X/Y/Z_HOME_BUMP_MM to 0.
* M914 X/Y/Z to live tune the setting
*/
//#define SENSORLESS_HOMING // TMC2130 only
#if ENABLED(SENSORLESS_HOMING)
#define X_HOMING_SENSITIVITY 8
#define Y_HOMING_SENSITIVITY 8
#define Z_HOMING_SENSITIVITY 8
#endif
/**
@@ -1136,6 +1216,22 @@
*/
//#define TMC_DEBUG
/**
* M915 Z Axis Calibration
*
* - Adjust Z stepper current,
* - Drive the Z axis to its physical maximum, and
* - Home Z to account for the lost steps.
*
* Use M915 Snn to specify the current.
* Use M925 Znn to add extra Z height to Z_MAX_POS.
*/
//#define TMC_Z_CALIBRATION
#if ENABLED(TMC_Z_CALIBRATION)
#define CALIBRATION_CURRENT 250
#define CALIBRATION_EXTRA_HEIGHT 10
#endif
/**
* You can set your own advanced settings by filling in predefined functions.
* A list of available functions can be found on the library github page
@@ -1148,85 +1244,61 @@
* stepperY.interpolate(0); \
* }
*/
#define TMC_ADV() { }
#define TMC_ADV() { }
#endif // TMC2130 || TMC2208
// @section L6470
/**
* Enable this section if you have L6470 motor drivers.
* You need to import the L6470 library into the Arduino IDE for this.
* (https://github.com/ameyer/Arduino-L6470)
* L6470 Stepper Driver options
*
* The Arduino-L6470 library is required for this stepper driver.
* https://github.com/ameyer/Arduino-L6470
*/
//#define HAVE_L6470DRIVER
#if ENABLED(HAVE_L6470DRIVER)
//#define X_IS_L6470
//#define X2_IS_L6470
//#define Y_IS_L6470
//#define Y2_IS_L6470
//#define Z_IS_L6470
//#define Z2_IS_L6470
//#define E0_IS_L6470
//#define E1_IS_L6470
//#define E2_IS_L6470
//#define E3_IS_L6470
//#define E4_IS_L6470
#if HAS_DRIVER(L6470)
#define X_MICROSTEPS 16 // number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be careful not to go too high
#define X_OVERCURRENT 2000 // maxc current in mA. If the current goes over this value, the driver will switch off
#define X_STALLCURRENT 1500 // current in mA where the driver will detect a stall
#define X2_MICROSTEPS 16
#define X2_K_VAL 50
#define X2_OVERCURRENT 2000
#define X2_STALLCURRENT 1500
#define Y_MICROSTEPS 16
#define Y_K_VAL 50
#define Y_OVERCURRENT 2000
#define Y_STALLCURRENT 1500
#define Y2_MICROSTEPS 16
#define Y2_K_VAL 50
#define Y2_OVERCURRENT 2000
#define Y2_STALLCURRENT 1500
#define Z_MICROSTEPS 16
#define Z_K_VAL 50
#define Z_OVERCURRENT 2000
#define Z_STALLCURRENT 1500
#define Z2_MICROSTEPS 16
#define Z2_K_VAL 50
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_K_VAL 50
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500
#define E1_MICROSTEPS 16
#define E1_K_VAL 50
#define E1_OVERCURRENT 2000
#define E1_STALLCURRENT 1500
#define E2_MICROSTEPS 16
#define E2_K_VAL 50
#define E2_OVERCURRENT 2000
#define E2_STALLCURRENT 1500
#define E3_MICROSTEPS 16
#define E3_K_VAL 50
#define E3_OVERCURRENT 2000
#define E3_STALLCURRENT 1500
#define E4_MICROSTEPS 16
#define E4_K_VAL 50
#define E4_OVERCURRENT 2000
#define E4_STALLCURRENT 1500
@@ -1485,7 +1557,7 @@
//#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper
// steps per full revolution (motor steps/rev * microstepping)
//#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction.
#define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_MICROSTEP // Type of error error correction.
#define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the
// printer will attempt to correct the error; errors
// smaller than this are ignored to minimize effects of
@@ -1497,7 +1569,7 @@
#define I2CPE_ENC_2_TICKS_UNIT 2048
//#define I2CPE_ENC_2_TICKS_REV (16 * 200)
//#define I2CPE_ENC_2_INVERT
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE
#define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_MICROSTEP
#define I2CPE_ENC_2_EC_THRESH 0.10
#define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options
@@ -1529,7 +1601,7 @@
* this setting determines the minimum update time between checks. A value of 100 works well with
* error rolling average when attempting to correct only for skips and not for vibration.
*/
#define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks.
#define I2CPE_MIN_UPD_TIME_MS 4 // (ms) Minimum time between encoder checks.
// Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise.
#define I2CPE_ERR_ROLLING_AVERAGE
@@ -1539,27 +1611,29 @@
/**
* MAX7219 Debug Matrix
*
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip, which can be used as a status
* display. Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*
* Fully assembled MAX7219 boards can be found on the internet for under $2(US).
* For example, see https://www.ebay.com/sch/i.html?_nkw=332349290049
* Add support for a low-cost 8x8 LED Matrix based on the Max7219 chip as a realtime status display.
* Requires 3 signal wires. Some useful debug options are included to demonstrate its usage.
*/
//#define MAX7219_DEBUG
#if ENABLED(MAX7219_DEBUG)
#define MAX7219_CLK_PIN 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display
#define MAX7219_DIN_PIN 57 // 78 on Re-ARM
#define MAX7219_LOAD_PIN 44 // 79 on Re-ARM
#define MAX7219_CLK_PIN 64
#define MAX7219_DIN_PIN 57
#define MAX7219_LOAD_PIN 44
//#define MAX7219_GCODE // Add the M7219 G-code to control the LED matrix
#define MAX7219_INIT_TEST 2 // Do a test pattern at initialization (Set to 2 for spiral)
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
/**
* Sample debug features
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_STEPPER_HEAD 3 // Show the stepper queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_TAIL 5 // Show the stepper queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_STEPPER_QUEUE 0 // Show the current stepper queue depth on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#endif
@@ -1577,4 +1651,7 @@
// Default behaviour is limited to Z axis only.
#endif
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#endif // CONFIGURATION_ADV_H

View File

@@ -21,80 +21,35 @@
*/
/**
* Tongue-in-cheek placeholder for a more Marlin-specific bitmap
* The joke is that every "CR-10" has different branding!
* Made using The Gimp and...
* - http://www.digole.com/tools/PicturetoC_Hex_converter.php
* Custom Boot Screen bitmap
*
* Place this file in the root with your configuration files
* and enable SHOW_CUSTOM_BOOTSCREEN in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#include <avr/pgmspace.h>
#define CUSTOM_BOOTSCREEN_TIMEOUT 2500
#define CUSTOM_BOOTSCREEN_BMPWIDTH 54
#define CUSTOM_BOOTSCREEN_BMPHEIGHT 64
#define CUSTOM_BOOTSCREEN_TIMEOUT 1000
#define CUSTOM_BOOTSCREEN_BMPWIDTH 128
const unsigned char custom_start_bmp[] PROGMEM = {
0x00, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00,
0x00, 0x00, 0x00, 0x3F, 0xF8, 0x00, 0x00,
0x00, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0x3F, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x0F, 0xF0,
0x00, 0x00, 0xFF, 0xFF, 0xFD, 0xFF, 0xF8,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8,
0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0,
0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0,
0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00,
0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00,
0x7F, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x7F, 0xFC, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x1F, 0x80, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0xFF, 0xFF, 0xFE, 0x3F, 0xF8,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8,
0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xC0,
0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xFE, 0x00,
0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xE0, 0x00,
0x00, 0x00, 0x07, 0xFF, 0xFC, 0x00, 0x00,
0x00, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00
};
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111100,B00000000,B00000000,
B00001111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000001,B10000110,B00011111,B11000000,
B00011000,B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00111100,B00001100,B00000000,B00000000,B00000001,B10000011,B00001100,B01100000,
B00010000,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00111100,B00001100,B00000000,B00000000,B00000001,B10000011,B00001100,B00110000,
B00110000,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00001100,B00000000,B00000000,B00000000,B00000011,B00001100,B00011000,
B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00111111,B00001111,B00111100,B00000000,B00000011,B00001100,B00001100,
B01100000,B00000001,B11011111,B00001111,B11100000,B11111110,B00000000,B01100000,B00011100,B00011100,B00000110,B00011000,B00000000,B00000110,B00001100,B00001100,
B01100000,B00000000,B11110011,B00011000,B00110001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000011,B00011000,B00000000,B00011110,B00001100,B00001100,
B01100000,B00000000,B11100000,B00110000,B00111001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000011,B00001100,B00001100,
B01100000,B00000000,B11000000,B00110000,B00111000,B00001111,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000001,B10001100,B00001100,
B01100000,B00000000,B11000000,B00111111,B11111000,B11111011,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000001,B10001100,B00001100,
B01100000,B00110000,B11000000,B00110000,B00000001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000001,B11110000,B00000001,B10000001,B10001100,B00001100,
B01100000,B00110000,B11000000,B00110000,B00000001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000000,B11100000,B00000001,B10000001,B10001100,B00011000,
B00110000,B00110000,B11000000,B00011000,B00110001,B10000011,B00000000,B01100000,B00001100,B00001100,B01000000,B11100000,B00000001,B10000011,B10001100,B00110000,
B00011000,B01100000,B11000000,B00001100,B01100001,B10000111,B11000000,B11100000,B00011100,B00001100,B11000000,B01100000,B00000000,B11000011,B00001100,B01100000,
B00001111,B11000011,B11110000,B00000111,B11000000,B11111111,B11000111,B11111100,B01111111,B00000111,B10000001,B11000000,B00000000,B01111110,B00011111,B11000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000000,B00000000,B00000000,B00000000,B00000000
};

View File

@@ -0,0 +1,80 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Status Screen bitmap
*
* Place this file in the root with your configuration files
* and enable CUSTOM_STATUS_SCREEN_IMAGE in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define STATUS_SCREENWIDTH 128
#define STATUS_SCREEN_HOTEND_TEXT_X(E) 38
#define STATUS_SCREEN_BED_TEXT_X 73
//============================================
const unsigned char status_screen0_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B11111100,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11111100,B00010000,
B00000000,B00111110,B00001111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B11000001,B10000110,B00011000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B11000001,B10000110,B00001100,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00000000,B11010000,
B00000000,B00000001,B10000110,B00000100,B00000000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B00000000,B00000011,B00000110,B00000100,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B00000000,B00011111,B00000110,B00000100,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B00000000,B00000011,B00000110,B00000100,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B00000000,B00000001,B10000110,B00000100,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101100,B00000000,B11010000,
B00000000,B11000001,B10000110,B00001100,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B11000001,B10000110,B00011000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00111110,B00001111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100000,B11111100,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110000,B11111100,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110011,B10000111,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B10000111,B10010000,
B00000000,B00111110,B00001111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B11000001,B10000110,B00011000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B11000001,B10000110,B00001100,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00000011,B11010000,
B00000000,B00000001,B10000110,B00000100,B00000000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B00000011,B00000110,B00000100,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00011111,B00000110,B00000100,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00000011,B00000110,B00000100,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B00000001,B10000110,B00000100,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101111,B00000011,B11010000,
B00000000,B11000001,B10000110,B00001100,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B11000001,B10000110,B00011000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B00111110,B00001111,B11110000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100111,B10000111,B10010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110011,B10000111,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,55 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Boot Screen bitmap
*
* Place this file in the root with your configuration files
* and enable SHOW_CUSTOM_BOOTSCREEN in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define CUSTOM_BOOTSCREEN_TIMEOUT 1000
#define CUSTOM_BOOTSCREEN_BMPWIDTH 128
const unsigned char custom_start_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111100,B00000000,B00000000,
B00001111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000001,B10000110,B00011111,B11000000,
B00011000,B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00111100,B00001100,B00000000,B00000000,B00000001,B10000011,B00001100,B01100000,
B00010000,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00111100,B00001100,B00000000,B00000000,B00000001,B10000011,B00001100,B00110000,
B00110000,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00001100,B00000000,B00000000,B00000000,B00000011,B00001100,B00011000,
B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00111111,B00001111,B00111100,B00000000,B00000011,B00001100,B00001100,
B01100000,B00000001,B11011111,B00001111,B11100000,B11111110,B00000000,B01100000,B00011100,B00011100,B00000110,B00011000,B00000000,B00000110,B00001100,B00001100,
B01100000,B00000000,B11110011,B00011000,B00110001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000011,B00011000,B00000000,B00011110,B00001100,B00001100,
B01100000,B00000000,B11100000,B00110000,B00111001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000011,B00001100,B00001100,
B01100000,B00000000,B11000000,B00110000,B00111000,B00001111,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000001,B10001100,B00001100,
B01100000,B00000000,B11000000,B00111111,B11111000,B11111011,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000001,B10001100,B00001100,
B01100000,B00110000,B11000000,B00110000,B00000001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000001,B11110000,B00000001,B10000001,B10001100,B00001100,
B01100000,B00110000,B11000000,B00110000,B00000001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000000,B11100000,B00000001,B10000001,B10001100,B00011000,
B00110000,B00110000,B11000000,B00011000,B00110001,B10000011,B00000000,B01100000,B00001100,B00001100,B01000000,B11100000,B00000001,B10000011,B10001100,B00110000,
B00011000,B01100000,B11000000,B00001100,B01100001,B10000111,B11000000,B11100000,B00011100,B00001100,B11000000,B01100000,B00000000,B11000011,B00001100,B01100000,
B00001111,B11000011,B11110000,B00000111,B11000000,B11111111,B11000111,B11111100,B01111111,B00000111,B10000001,B11000000,B00000000,B01111110,B00011111,B11000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000000,B00000000,B00000000,B00000000,B00000000
};

View File

@@ -0,0 +1,452 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Status Screen bitmap
*
* Place this file in the root with your configuration files
* and enable CUSTOM_STATUS_SCREEN_IMAGE in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define STATUS_SCREENWIDTH 128
#define STATUS_SCREEN_HOTEND_TEXT_X(E) (38 + (E) * 20)
#define STATUS_SCREEN_BED_TEXT_X (HOTENDS > 1 ? 81 : 73)
// Can also be overridden in Configuration.h
#ifndef FAN_ANIM_FRAMES
#define FAN_ANIM_FRAMES 3
#endif
#define STATUS_SCREEN_FAN_TEXT_X (FAN_ANIM_FRAMES == 3 ? 103 : 105)
#define STATUS_SCREEN_FAN_TEXT_Y (FAN_ANIM_FRAMES > 2 ? 28 : 27)
//============================================
#if HOTENDS < 2
#if FAN_ANIM_FRAMES <= 2
const unsigned char status_screen0_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B11111100,B00110000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11111100,B00010000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B01111000,B00010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B00110000,B00010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00000000,B11010000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101100,B00000000,B11010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100000,B11111100,B00010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110000,B11111100,B00110000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110011,B10000111,B00110000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B10000111,B10010000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00000011,B11010000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101111,B00000011,B11010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100111,B10000111,B10010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110011,B10000111,B00110000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};
#elif FAN_ANIM_FRAMES == 3
const unsigned char status_screen0_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11000000,B00011111,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00100000,B00100111,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B11110000,B01111011,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B11110000,B01111011,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000101,B11111000,B11111101,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B11111000,B11111001,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000100,B00111111,B11100001,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00000100,B00001111,B10000001,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00000100,B00001111,B10000001,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000100,B00001111,B10000001,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00000100,B00111111,B11100001,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00000100,B11111000,B11111001,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00000101,B11111000,B11111101,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00000110,B11110000,B01111011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000110,B11110000,B01111011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00100000,B00100111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000111,B11000000,B00011111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000111,B11111111,B11111111
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11000110,B00011111,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00111110,B00000111,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B00111110,B00000011,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B00011110,B00000011,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00011110,B00001101,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00000110,B00111101,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000100,B00000111,B00111101,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00000100,B00001111,B11111111,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00000111,B11111111,B11111111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000111,B11111111,B10000001,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00000101,B11100111,B00000001,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00000101,B11000011,B00000001,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00000101,B10000011,B11000001,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00000110,B00000011,B11000011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000110,B00000011,B11100011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000011,B11100111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000111,B11000011,B00011111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000111,B11111111,B11111111
};
const unsigned char status_screen2_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11000011,B00011111,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000011,B11100111,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B00000011,B11110011,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B10000011,B11100011,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000101,B11000011,B11000001,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000101,B11100011,B10000001,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000101,B11110111,B00000001,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00000111,B11111111,B10000001,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00000111,B11111111,B11111111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000100,B00001111,B11111111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00000100,B00000111,B01111101,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00000100,B00001110,B00111101,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00000100,B00011110,B00011101,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00000110,B00111110,B00001011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00000110,B01111110,B00000011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00111110,B00000111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000111,B11000110,B00011111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000111,B11111111,B11111111
};
#elif FAN_ANIM_FRAMES == 4
const unsigned char status_screen0_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B00000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00111111,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B01111110,B00011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B01111100,B00011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101000,B01111100,B00001000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00111000,B00001000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101111,B00111001,B11001000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B11111111,B11101000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B11000111,B11101000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101111,B11111111,B11101000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100111,B00111001,B11101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B00111000,B01101000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B01111100,B00101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00110000,B01111100,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110000,B11111100,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111001,B11111000,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111110,B00000000,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11111000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B00000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00001111,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110100,B00011111,B11011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110110,B00011111,B10011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00011111,B00001000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10011110,B00001000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101111,B11111100,B00001000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B11011100,B00001000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100111,B11101111,B11001000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B01110111,B11101000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100000,B01111111,B11101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B11110011,B11101000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100001,B11110001,B11101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00110011,B11110000,B11011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110111,B11110000,B01011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111001,B11100000,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111110,B00000000,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11111000
};
const unsigned char status_screen2_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B10000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111001,B10000000,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110111,B10000001,B11011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110111,B11000011,B11011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B11000111,B11101000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100011,B11000111,B11111000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100001,B11111111,B10001000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01101100,B00001000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01101100,B00001000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B01101100,B00001000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100011,B11111111,B00001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00111111,B11000111,B10001000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B11000111,B11001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00110111,B10000111,B11011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110111,B00000011,B11011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000011,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111110,B00000010,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11111000
};
const unsigned char status_screen3_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B00000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111001,B11110000,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110001,B11100000,B00011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110001,B11100000,B00011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100001,B11100001,B11101000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11110011,B11101000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B01111111,B11101000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01110111,B11101000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101000,B11101110,B00101000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101111,B11011100,B00001000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101111,B11111100,B00001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10011110,B00001000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B00001111,B00001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00110000,B00001111,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110000,B00001111,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00011111,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111110,B00000000,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11111000
};
#endif
#else // HOTENDS >= 2
#if FAN_ANIM_FRAMES <= 2
const unsigned char status_screen0_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B11111100,B00110000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11111100,B00010000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B01111000,B00010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B00110000,B00010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00000000,B11010000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00101110,B00110001,B11010000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00101111,B01111011,B11010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00101111,B01111011,B11010000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00101110,B00110001,B11010000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00101100,B00000000,B11010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00100000,B00110000,B00010000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00100000,B01111000,B00010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00100000,B11111100,B00010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110000,B11111100,B00110000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11110000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110011,B10000111,B00110000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B10000111,B10010000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00000011,B11010000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00100000,B00110000,B00010000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00100000,B01111000,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00100000,B01111000,B00010000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00100000,B00110000,B00010000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00101111,B00000011,B11010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00101111,B10000111,B11010000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00101111,B10000111,B11010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00100111,B10000111,B10010000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110011,B10000111,B00110000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11110000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000
};
#elif FAN_ANIM_FRAMES == 3
const unsigned char status_screen0_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11000000,B00011111,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00100000,B00100111,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B11110000,B01111011,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B11110000,B01111011,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000101,B11111000,B11111101,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B11111000,B11111001,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00000100,B00111111,B11100001,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00000100,B00001111,B10000001,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00000100,B00001111,B10000001,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00000100,B00001111,B10000001,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00000100,B00111111,B11100001,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00000100,B11111000,B11111001,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00000101,B11111000,B11111101,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00000110,B11110000,B01111011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00000110,B11110000,B01111011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00000111,B00100000,B00100111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00000111,B11000000,B00011111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00000111,B11111111,B11111111
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11000110,B00011111,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00111110,B00000111,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B00111110,B00000011,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B00011110,B00000011,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00011110,B00001101,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000100,B00000110,B00111101,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00000100,B00000111,B00111101,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00000100,B00001111,B11111111,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00000111,B11111111,B11111111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00000111,B11111111,B10000001,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00000101,B11100111,B00000001,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00000101,B11000011,B00000001,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00000101,B10000011,B11000001,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00000110,B00000011,B11000011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00000110,B00000011,B11100011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00000111,B00000011,B11100111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00000111,B11000011,B00011111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00000111,B11111111,B11111111
};
const unsigned char status_screen2_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11111111,B11111111,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B11000011,B00011111,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000011,B11100111,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B00000011,B11110011,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000110,B10000011,B11100011,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000101,B11000011,B11000001,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000101,B11100011,B10000001,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00000101,B11110111,B00000001,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00000111,B11111111,B10000001,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00000111,B11111111,B11111111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00000100,B00001111,B11111111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00000100,B00000111,B01111101,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00000100,B00001110,B00111101,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00000100,B00011110,B00011101,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00000110,B00111110,B00001011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00000110,B01111110,B00000011,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00000111,B00111110,B00000111,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00000111,B11000110,B00011111,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00000111,B11111111,B11111111
};
#elif FAN_ANIM_FRAMES == 4
const unsigned char status_screen0_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B00000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00111111,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B01111110,B00011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B01111100,B00011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101000,B01111100,B00001000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00111000,B00001000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00101111,B00111001,B11001000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00101111,B11111111,B11101000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00101111,B11000111,B11101000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00101111,B11111111,B11101000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00100111,B00111001,B11101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00100000,B00111000,B01101000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00100000,B01111100,B00101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00110000,B01111100,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110000,B11111100,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111001,B11111000,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111110,B00000000,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11111000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B00000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00001111,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110100,B00011111,B11011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110110,B00011111,B10011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00011111,B00001000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10011110,B00001000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00101111,B11111100,B00001000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00101111,B11011100,B00001000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00100111,B11101111,B11001000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00100000,B01110111,B11101000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00100000,B01111111,B11101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00100000,B11110011,B11101000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00100001,B11110001,B11101000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00110011,B11110000,B11011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110111,B11110000,B01011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111001,B11100000,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111110,B00000000,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11111000
};
const unsigned char status_screen2_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B10000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111001,B10000000,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110111,B10000001,B11011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110111,B11000011,B11011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B11000111,B11101000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100011,B11000111,B11111000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00100001,B11111111,B10001000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00100000,B01101100,B00001000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00100000,B01101100,B00001000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00100000,B01101100,B00001000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00100011,B11111111,B00001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00111111,B11000111,B10001000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00101111,B11000111,B11001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00110111,B10000111,B11011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110111,B00000011,B11011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111000,B00000011,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111110,B00000010,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11111000
};
const unsigned char status_screen3_bmp[] PROGMEM = {
B00111101,B11110000,B00000010,B00111000,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11111000,
B01000100,B10001000,B00000110,B01000101,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111110,B00000000,B11111000,
B10000000,B10001000,B00000010,B01000101,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111001,B11110000,B00111000,
B10000000,B11110000,B00000010,B01000100,B10000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110001,B11100000,B00011000,
B10000000,B10100011,B11110010,B01000100,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110001,B11100000,B00011000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100001,B11100001,B11101000,
B10000000,B10010000,B00000010,B01000100,B00010000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11110011,B11101000,
B01000100,B10001000,B00000010,B01000101,B00010000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00100000,B01111111,B11101000,
B00111001,B11001100,B00000111,B00111001,B11100000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00100000,B01110111,B11101000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00101000,B11101110,B00101000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00101111,B11011100,B00001000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00101111,B11111100,B00001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00101111,B10011110,B00001000,
B00000000,B00011000,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00101111,B00001111,B00001000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00110000,B00001111,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110000,B00001111,B00011000,
B00000000,B00000100,B10001001,B00010000,B00000000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111000,B00011111,B00111000,
B00000000,B01000100,B10001001,B00010000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111110,B00000000,B11111000,
B00000000,B00111000,B01110000,B11100000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11111000
};
#endif
#endif // HOTENDS >= 2

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,55 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Boot Screen bitmap
*
* Place this file in the root with your configuration files
* and enable SHOW_CUSTOM_BOOTSCREEN in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define CUSTOM_BOOTSCREEN_TIMEOUT 1000
#define CUSTOM_BOOTSCREEN_BMPWIDTH 128
const unsigned char custom_start_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00000000,B00000000,B00000000,B00000000,B11111100,B00000000,B00000000,
B00001111,B11110000,B00000000,B00000000,B00000000,B00000000,B00000111,B11100000,B00000000,B00000000,B00000000,B00000000,B00000001,B10000110,B00011111,B11000000,
B00011000,B01110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00111100,B00001100,B00000000,B00000000,B00000001,B10000011,B00001100,B01100000,
B00010000,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00111100,B00001100,B00000000,B00000000,B00000001,B10000011,B00001100,B00110000,
B00110000,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00001100,B00000000,B00000000,B00000000,B00000011,B00001100,B00011000,
B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B01100000,B00000000,B00111111,B00001111,B00111100,B00000000,B00000011,B00001100,B00001100,
B01100000,B00000001,B11011111,B00001111,B11100000,B11111110,B00000000,B01100000,B00011100,B00011100,B00000110,B00011000,B00000000,B00000110,B00001100,B00001100,
B01100000,B00000000,B11110011,B00011000,B00110001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000011,B00011000,B00000000,B00011110,B00001100,B00001100,
B01100000,B00000000,B11100000,B00110000,B00111001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000011,B00001100,B00001100,
B01100000,B00000000,B11000000,B00110000,B00111000,B00001111,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000001,B10001100,B00001100,
B01100000,B00000000,B11000000,B00111111,B11111000,B11111011,B00000000,B01100000,B00001100,B00001100,B00000011,B00110000,B00000000,B00000001,B10001100,B00001100,
B01100000,B00110000,B11000000,B00110000,B00000001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000001,B11110000,B00000001,B10000001,B10001100,B00001100,
B01100000,B00110000,B11000000,B00110000,B00000001,B10000011,B00000000,B01100000,B00001100,B00001100,B00000000,B11100000,B00000001,B10000001,B10001100,B00011000,
B00110000,B00110000,B11000000,B00011000,B00110001,B10000011,B00000000,B01100000,B00001100,B00001100,B01000000,B11100000,B00000001,B10000011,B10001100,B00110000,
B00011000,B01100000,B11000000,B00001100,B01100001,B10000111,B11000000,B11100000,B00011100,B00001100,B11000000,B01100000,B00000000,B11000011,B00001100,B01100000,
B00001111,B11000011,B11110000,B00000111,B11000000,B11111111,B11000111,B11111100,B01111111,B00000111,B10000001,B11000000,B00000000,B01111110,B00011111,B11000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000000,B00000000,B00000000,B00000000,B00000000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B00000000,B00000000,B00000000,B00000000,B00000000
};

View File

@@ -0,0 +1,80 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Status Screen bitmap
*
* Place this file in the root with your configuration files
* and enable CUSTOM_STATUS_SCREEN_IMAGE in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define STATUS_SCREENWIDTH 128
#define STATUS_SCREEN_HOTEND_TEXT_X(E) 38
#define STATUS_SCREEN_BED_TEXT_X 73
//============================================
const unsigned char status_screen0_bmp[] PROGMEM = {
B00000111,B11001111,B10000000,B00110001,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00001111,B11001111,B11000000,B01110011,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00001100,B00001100,B01000000,B01110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B11111100,B00110000,
B00001100,B00001100,B11000000,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11111100,B00010000,
B00001100,B00001111,B11001111,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B01111000,B00010000,
B00001100,B00001101,B10001111,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B00110000,B00010000,
B00001100,B00001100,B11000000,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00000000,B11010000,
B00001111,B11001100,B11000000,B00110011,B11110000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B00000111,B11001100,B11000000,B00110001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B00000001,B10000011,B00110000,B00000011,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B00000001,B10000011,B00110010,B00000011,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101100,B00000000,B11010000,
B00000001,B11000111,B00000010,B11100000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B00110000,B00010000,
B00000001,B11000111,B00110011,B11110011,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B01111000,B00010000,
B00000001,B11101111,B00110011,B00110011,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100000,B11111100,B00010000,
B00000001,B10111011,B00110011,B00110011,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110000,B11111100,B00110000,
B00000001,B10010011,B00110011,B00110011,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000001,B10010011,B00110011,B00110011,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000001,B10000011,B00110011,B00110011,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00000111,B11001111,B10000000,B00110001,B11100000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00001111,B11001111,B11000000,B01110011,B11110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00001100,B00001100,B01000000,B01110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110011,B10000111,B00110000,
B00001100,B00001100,B11000000,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B10000111,B10010000,
B00001100,B00001111,B11001111,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00001100,B00001101,B10001111,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00001100,B00001100,B11000000,B00110011,B00110000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00000011,B11010000,
B00001111,B11001100,B11000000,B00110011,B11110000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B00000111,B11001100,B11000000,B00110001,B11100000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B00000001,B10000011,B00110000,B00000011,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B00000001,B10000011,B00110010,B00000011,B00000000,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101111,B00000011,B11010000,
B00000001,B11000111,B00000010,B11100000,B00000000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000001,B11000111,B00110011,B11110011,B00000000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000001,B11101111,B00110011,B00110011,B00000000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100111,B10000111,B10010000,
B00000001,B10111011,B00110011,B00110011,B00000000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110011,B10000111,B00110000,
B00000001,B10010011,B00110011,B00110011,B00000000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000001,B10010011,B00110011,B00110011,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000001,B10000011,B00110011,B00110011,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,18 @@
# Creality Ender Support
This branch is a reverse-engineered version based on the unpublished firmware from Creality. It is **not** the authoritative source, but has been carefully re-built by looking at their firmware and inferring the base version and configuration they used. The basis is the firmware version from "Jul 31 2017 10:16:30". It is based on Marlin 1.0.1, because
* 1.0.0 had very different serial output in `setup()` and overall code structure.
* 1.0.2 changed the `VERSION_STRING` to include a leading space, and `lcd_init` uses `SET_INPUT` instead of `pinMode`.
Configurations were found by seeing what code was compiled into the firmware, and constants used there.
For U8Glib, at least version 1.14 and at most 1.17 is used, because
* 1.12 didn't have the extra speed argument to u8g_InitCom.
* 1.13 didn't have the soft reset instruction for UC1701 initialization.
* 1.18 has a new directory structure.
## Bitmaps
The bootscreen and custom status screens come from Creality's firmware.

View File

@@ -0,0 +1,96 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Boot Screen bitmap
*
* Place this file in the root with your configuration files
* and enable SHOW_CUSTOM_BOOTSCREEN in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define CUSTOM_BOOTSCREEN_TIMEOUT 1000
#define CUSTOM_BOOTSCREEN_BMPWIDTH 81
#define CUSTOM_BOOTSCREEN_INVERTED
const unsigned char custom_start_bmp[] PROGMEM = {
B11111111,B11111111,B11111111,B11111111,B11101111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11101111,B11101111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11100111,B11011111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11100111,B11011111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11100011,B11011111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11110011,B11001111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11100001,B11100001,B11001111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111110,B01111000,B00000000,B00000000,B00000011,B11011101,B11111111,B11111111,B11111111,B11111111,
B11111110,B11111111,B10000000,B01111110,B00000000,B00000001,B11101110,B11111111,B11111111,B11111111,B11111111,
B11111110,B01111101,B11001111,B11111100,B00000000,B00000000,B11110111,B01111111,B11111111,B11111111,B11111111,
B11111111,B10001110,B00000110,B00000000,B00000000,B00000000,B01111011,B10111111,B11111111,B11111111,B11111111,
B11111111,B11000000,B00000000,B00000000,B00000000,B00000000,B01111101,B11011111,B11111111,B11111111,B11111111,
B11111111,B11111100,B00000001,B11111110,B00000000,B00000000,B00111110,B11100111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111100,B00000000,B00000011,B00011111,B01110011,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111000,B00000000,B00000001,B10001111,B10000001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11100000,B00000000,B00000000,B10000011,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B00000000,B11111100,B00000000,B00000000,B11110000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11100000,B00001111,B11111111,B11000000,B00000000,B00000000,B11111111,B11111111,B11111111,
B11111111,B11111110,B00000011,B11111111,B11111111,B11000000,B00000000,B00000000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111001,B00000000,B00000000,B00000000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111100,B00000000,B00000111,B11000000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B00000000,B00000111,B11100000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11100000,B00000111,B11110001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111100,B00000111,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B00000011,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B10000011,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11000011,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11100001,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11110000,B10111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111011,B11111000,B00111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111001,B11111000,B00111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B01111110,B11110000,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B10001110,B00000011,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11100000,B00011111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B01111111,B11111111,B11111111,B11111111,
B11111111,B00000000,B00000000,B01111111,B11111111,B11111111,B11111000,B01111111,B11111111,B11111111,B11111111,
B11111111,B10000000,B00000000,B01111111,B11111111,B11111111,B11100000,B01111111,B11111111,B11111111,B11111111,
B11111111,B11000011,B11111100,B11111111,B11111111,B11111111,B11111000,B11111111,B11111111,B11111111,B11111111,
B11111111,B11000011,B11111100,B11111111,B11111111,B11111111,B11111000,B11111111,B11111111,B11111111,B11111111,
B11111111,B10000111,B11111101,B11111111,B11111111,B11111111,B11110001,B11111111,B11111111,B11111111,B11111111,
B11111111,B10000111,B11111111,B11111111,B11111111,B11111111,B11110001,B11111111,B11111111,B11111111,B11111111,
B11111111,B00001111,B11100111,B11110011,B00001111,B11111100,B00100011,B11111100,B00111111,B11111111,B11111111,
B11111111,B00001111,B11101111,B10000000,B00000111,B11110000,B00000011,B11110000,B00011110,B00000000,B01111111,
B11111110,B00011111,B11001111,B10000001,B10000111,B11000111,B10000111,B11000111,B00001100,B00000000,B01111111,
B11111110,B00000000,B00011111,B11000111,B11000111,B10001111,B11000111,B10011111,B00001111,B00001100,B11111111,
B11111110,B00000000,B00011111,B10000111,B10001111,B00011111,B10001111,B00011111,B00001111,B00011111,B11111111,
B11111100,B00111111,B10011111,B10001111,B10001111,B00011111,B10001110,B00000000,B00011110,B00111111,B11111111,
B11111100,B01111111,B00111111,B00001111,B00011110,B00111111,B00011110,B00111111,B11111110,B00111111,B11111111,
B11111000,B01111111,B11111111,B00011111,B00011100,B00111111,B00011100,B01111111,B11111100,B01111111,B11111111,
B11111000,B11111111,B11111111,B00011110,B00011100,B01111110,B00011100,B01111111,B11111100,B01111111,B11111111,
B11110000,B11111111,B11001110,B00111110,B00111100,B01111110,B00111100,B01111111,B10111000,B11111111,B11111111,
B11110000,B11111111,B10011110,B00111100,B00111000,B01111100,B00111000,B01111110,B01111000,B11111111,B11111111,
B11100001,B11111111,B00111100,B01111100,B01111000,B01111100,B01111000,B00111100,B11110001,B11111111,B11111111,
B11100001,B11111000,B00111000,B01111000,B01111000,B00010000,B00011000,B00000001,B11110001,B11111111,B11111111,
B00000000,B00000000,B01100000,B00100000,B00111100,B00000000,B01111100,B00000111,B10000000,B01111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111110,B00011111,B11111110,B00011111,B11111111,B11111111,B11111111
};

View File

@@ -0,0 +1,130 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Status Screen bitmap
*
* Place this file in the root with your configuration files
* and enable CUSTOM_STATUS_SCREEN_IMAGE in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define STATUS_SCREENWIDTH 128
#define STATUS_SCREEN_HOTEND_TEXT_X(E) (38 + (E) * 20)
#define STATUS_SCREEN_BED_TEXT_X (HOTENDS > 1 ? 81 : 73)
#define STATUS_SCREEN_FAN_TEXT_X 103
//============================================
#if HOTENDS < 2
const unsigned char status_screen0_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B11111100,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11111100,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B00000000,B00000110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00000000,B11010000,
B11111110,B00000000,B00000010,B00000000,B00000000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B01000010,B00000000,B00000010,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B01001000,B00000000,B00000010,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00101111,B01111011,B11010000,
B01001000,B11011100,B00111110,B00111100,B11101110,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00101110,B00110001,B11010000,
B01111000,B01100010,B01000010,B01000010,B00110010,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101100,B00000000,B11010000,
B01001000,B01000010,B01000010,B01000010,B00100000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B00110000,B00010000,
B01001000,B01000010,B01000010,B01111110,B00100000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00100000,B01111000,B00010000,
B01000000,B01000010,B01000010,B01000000,B00100000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100000,B11111100,B00010000,
B01000010,B01000010,B01000110,B01000010,B00100000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110000,B11111100,B00110000,
B11111110,B11100111,B00111011,B00111100,B11111000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110011,B10000111,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B10000111,B10010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B00000000,B00000110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00000011,B11010000,
B11111110,B00000000,B00000010,B00000000,B00000000,B00011111,B11100000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B01000010,B00000000,B00000010,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B01001000,B00000000,B00000010,B00000000,B00000000,B00111111,B11110000,B00000000,B00000000,B00000100,B00010000,B01000000,B00000000,B00100000,B01111000,B00010000,
B01001000,B11011100,B00111110,B00111100,B11101110,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00100000,B00110000,B00010000,
B01111000,B01100010,B01000010,B01000010,B00110010,B00011111,B11100000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00101111,B00000011,B11010000,
B01001000,B01000010,B01000010,B01000010,B00100000,B00011111,B11100000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B01001000,B01000010,B01000010,B01111110,B00100000,B00111111,B11110000,B00000000,B00000000,B00100000,B10000010,B00000000,B00000000,B00101111,B10000111,B11010000,
B01000000,B01000010,B01000010,B01000000,B00100000,B00111111,B11110000,B00000000,B00000000,B00010000,B01000001,B00000000,B00000000,B00100111,B10000111,B10010000,
B01000010,B01000010,B01000110,B01000010,B00100000,B00111111,B11110000,B00000000,B00000000,B00001000,B00100000,B10000000,B00000000,B00110011,B10000111,B00110000,
B11111110,B11100111,B00111011,B00111100,B11111000,B00001111,B11000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B10000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B00000000,B00000000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000,B00000000
};
#else // HOTENDS >= 2
const unsigned char status_screen0_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110000,B11111100,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B11111100,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B01111000,B00010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100000,B00110000,B00010000,
B00000000,B00000000,B00000110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101100,B00000000,B11010000,
B11111110,B00000000,B00000010,B00000000,B00000000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00101110,B00110001,B11010000,
B01000010,B00000000,B00000010,B00000000,B00000000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00101111,B01111011,B11010000,
B01001000,B00000000,B00000010,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00101111,B01111011,B11010000,
B01001000,B11011100,B00111110,B00111100,B11101110,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00101110,B00110001,B11010000,
B01111000,B01100010,B01000010,B01000010,B00110010,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00101100,B00000000,B11010000,
B01001000,B01000010,B01000010,B01000010,B00100000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00100000,B00110000,B00010000,
B01001000,B01000010,B01000010,B01111110,B00100000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00100000,B01111000,B00010000,
B01000000,B01000010,B01000010,B01000000,B00100000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00100000,B11111100,B00010000,
B01000010,B01000010,B01000110,B01000010,B00100000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110000,B11111100,B00110000,
B11111110,B11100111,B00111011,B00111100,B11111000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000
};
const unsigned char status_screen1_bmp[] PROGMEM = {
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00110011,B10000111,B00110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00100111,B10000111,B10010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B10000111,B11010000,
B00000000,B00000000,B00000110,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00000000,B00101111,B00000011,B11010000,
B11111110,B00000000,B00000010,B00000000,B00000000,B00011111,B11100000,B00000001,B11111110,B00000000,B00001000,B00100000,B10000000,B00100000,B00110000,B00010000,
B01000010,B00000000,B00000010,B00000000,B00000000,B00111110,B11110000,B00000011,B11001111,B00000000,B00000100,B00010000,B01000000,B00100000,B01111000,B00010000,
B01001000,B00000000,B00000010,B00000000,B00000000,B00111100,B11110000,B00000011,B10110111,B00000000,B00000100,B00010000,B01000000,B00100000,B01111000,B00010000,
B01001000,B11011100,B00111110,B00111100,B11101110,B00111010,B11110000,B00000011,B11110111,B00000000,B00001000,B00100000,B10000000,B00100000,B00110000,B00010000,
B01111000,B01100010,B01000010,B01000010,B00110010,B00011110,B11100000,B00000001,B11101110,B00000000,B00010000,B01000001,B00000000,B00101111,B00000011,B11010000,
B01001000,B01000010,B01000010,B01000010,B00100000,B00011110,B11100000,B00000001,B11011110,B00000000,B00100000,B10000010,B00000000,B00101111,B10000111,B11010000,
B01001000,B01000010,B01000010,B01111110,B00100000,B00111110,B11110000,B00000011,B10111111,B00000000,B00100000,B10000010,B00000000,B00101111,B10000111,B11010000,
B01000000,B01000010,B01000010,B01000000,B00100000,B00111110,B11110000,B00000011,B10000111,B00000000,B00010000,B01000001,B00000000,B00100111,B10000111,B10010000,
B01000010,B01000010,B01000110,B01000010,B00100000,B00111111,B11110000,B00000011,B11111111,B00000000,B00001000,B00100000,B10000000,B00110011,B10000111,B00110000,
B11111110,B11100111,B00111011,B00111100,B11111000,B00001111,B11000000,B00000000,B11111100,B00000000,B00000000,B00000000,B00000000,B00111000,B00000000,B01110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000111,B10000000,B00000000,B01111000,B00000000,B11111111,B11111111,B11000000,B00111111,B11111111,B11110000,
B00000000,B00000000,B00000000,B00000000,B00000000,B00000011,B00000000,B00000000,B00110000,B00000000,B11111111,B11111111,B11000000,B00000000,B00000000,B00000000
};
#endif // HOTENDS >= 2

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,18 @@
# Creality Ender Support
This branch is a reverse-engineered version based on the unpublished firmware from Creality. It is **not** the authoritative source, but has been carefully re-built by looking at their firmware and inferring the base version and configuration they used. The basis is the firmware version from "Jul 31 2017 10:16:30". It is based on Marlin 1.0.1, because
* 1.0.0 had very different serial output in `setup()` and overall code structure.
* 1.0.2 changed the `VERSION_STRING` to include a leading space, and `lcd_init` uses `SET_INPUT` instead of `pinMode`.
Configurations were found by seeing what code was compiled into the firmware, and constants used there.
For U8Glib, at least version 1.14 and at most 1.17 is used, because
* 1.12 didn't have the extra speed argument to u8g_InitCom.
* 1.13 didn't have the soft reset instruction for UC1701 initialization.
* 1.18 has a new directory structure.
## Bitmaps
The bootscreen and custom status screens come from Creality's firmware.

View File

@@ -0,0 +1,96 @@
/**
* 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 <http://www.gnu.org/licenses/>.
*
*/
/**
* Custom Boot Screen bitmap
*
* Place this file in the root with your configuration files
* and enable SHOW_CUSTOM_BOOTSCREEN in Configuration.h.
*
* Use the Marlin Bitmap Converter to make your own:
* http://marlinfw.org/tools/u8glib/converter.html
*/
#define CUSTOM_BOOTSCREEN_TIMEOUT 1000
#define CUSTOM_BOOTSCREEN_BMPWIDTH 81
#define CUSTOM_BOOTSCREEN_INVERTED
const unsigned char custom_start_bmp[] PROGMEM = {
B11111111,B11111111,B11111111,B11111111,B11101111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11101111,B11101111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11100111,B11011111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11100111,B11011111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11100011,B11011111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11110011,B11001111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11100001,B11100001,B11001111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111110,B01111000,B00000000,B00000000,B00000011,B11011101,B11111111,B11111111,B11111111,B11111111,
B11111110,B11111111,B10000000,B01111110,B00000000,B00000001,B11101110,B11111111,B11111111,B11111111,B11111111,
B11111110,B01111101,B11001111,B11111100,B00000000,B00000000,B11110111,B01111111,B11111111,B11111111,B11111111,
B11111111,B10001110,B00000110,B00000000,B00000000,B00000000,B01111011,B10111111,B11111111,B11111111,B11111111,
B11111111,B11000000,B00000000,B00000000,B00000000,B00000000,B01111101,B11011111,B11111111,B11111111,B11111111,
B11111111,B11111100,B00000001,B11111110,B00000000,B00000000,B00111110,B11100111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111100,B00000000,B00000011,B00011111,B01110011,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111000,B00000000,B00000001,B10001111,B10000001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11100000,B00000000,B00000000,B10000011,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B00000000,B11111100,B00000000,B00000000,B11110000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11100000,B00001111,B11111111,B11000000,B00000000,B00000000,B11111111,B11111111,B11111111,
B11111111,B11111110,B00000011,B11111111,B11111111,B11000000,B00000000,B00000000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111001,B00000000,B00000000,B00000000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111100,B00000000,B00000111,B11000000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B00000000,B00000111,B11100000,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11100000,B00000111,B11110001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111100,B00000111,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B00000011,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B10000011,B11111001,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11000011,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11100001,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11110000,B10111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111011,B11111000,B00111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111001,B11111000,B00111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B01111110,B11110000,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B10001110,B00000011,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11100000,B00011111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B11111111,B01111111,B11111111,B11111111,B11111111,
B11111111,B00000000,B00000000,B01111111,B11111111,B11111111,B11111000,B01111111,B11111111,B11111111,B11111111,
B11111111,B10000000,B00000000,B01111111,B11111111,B11111111,B11100000,B01111111,B11111111,B11111111,B11111111,
B11111111,B11000011,B11111100,B11111111,B11111111,B11111111,B11111000,B11111111,B11111111,B11111111,B11111111,
B11111111,B11000011,B11111100,B11111111,B11111111,B11111111,B11111000,B11111111,B11111111,B11111111,B11111111,
B11111111,B10000111,B11111101,B11111111,B11111111,B11111111,B11110001,B11111111,B11111111,B11111111,B11111111,
B11111111,B10000111,B11111111,B11111111,B11111111,B11111111,B11110001,B11111111,B11111111,B11111111,B11111111,
B11111111,B00001111,B11100111,B11110011,B00001111,B11111100,B00100011,B11111100,B00111111,B11111111,B11111111,
B11111111,B00001111,B11101111,B10000000,B00000111,B11110000,B00000011,B11110000,B00011110,B00000000,B01111111,
B11111110,B00011111,B11001111,B10000001,B10000111,B11000111,B10000111,B11000111,B00001100,B00000000,B01111111,
B11111110,B00000000,B00011111,B11000111,B11000111,B10001111,B11000111,B10011111,B00001111,B00001100,B11111111,
B11111110,B00000000,B00011111,B10000111,B10001111,B00011111,B10001111,B00011111,B00001111,B00011111,B11111111,
B11111100,B00111111,B10011111,B10001111,B10001111,B00011111,B10001110,B00000000,B00011110,B00111111,B11111111,
B11111100,B01111111,B00111111,B00001111,B00011110,B00111111,B00011110,B00111111,B11111110,B00111111,B11111111,
B11111000,B01111111,B11111111,B00011111,B00011100,B00111111,B00011100,B01111111,B11111100,B01111111,B11111111,
B11111000,B11111111,B11111111,B00011110,B00011100,B01111110,B00011100,B01111111,B11111100,B01111111,B11111111,
B11110000,B11111111,B11001110,B00111110,B00111100,B01111110,B00111100,B01111111,B10111000,B11111111,B11111111,
B11110000,B11111111,B10011110,B00111100,B00111000,B01111100,B00111000,B01111110,B01111000,B11111111,B11111111,
B11100001,B11111111,B00111100,B01111100,B01111000,B01111100,B01111000,B00111100,B11110001,B11111111,B11111111,
B11100001,B11111000,B00111000,B01111000,B01111000,B00010000,B00011000,B00000001,B11110001,B11111111,B11111111,
B00000000,B00000000,B01100000,B00100000,B00111100,B00000000,B01111100,B00000111,B10000000,B01111111,B11111111,
B11111111,B11111111,B11111111,B11111111,B11111110,B00011111,B11111110,B00011111,B11111111,B11111111,B11111111
};

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