Browse Source

Merge remote-tracking branch 'Marlin8bit/Development' into serial_wait

pull/1/head
Wurstnase 10 years ago
parent
commit
182e0d99c9
  1. 17
      Documentation/GCodes.md
  2. 206
      Documentation/Hardware.md
  3. 9
      Documentation/LCDLanguageFont.md
  4. 78
      Marlin/Configuration.h
  5. 6
      Marlin/Configuration_adv.h
  6. 4
      Marlin/Makefile
  7. 12
      Marlin/Marlin.h
  8. 509
      Marlin/Marlin_main.cpp
  9. 4
      Marlin/SanityCheck.h
  10. 4
      Marlin/blinkm.cpp
  11. 2
      Marlin/blinkm.h
  12. 329
      Marlin/configuration_store.cpp
  13. 6
      Marlin/configuration_store.h
  14. 74
      Marlin/configurator/config/Configuration.h
  15. 6
      Marlin/configurator/config/Configuration_adv.h
  16. 25
      Marlin/configurator/config/language.h
  17. 0
      Marlin/dogm_bitmaps.h
  18. 270
      Marlin/dogm_font_data_ISO10646_CN.h
  19. 42
      Marlin/dogm_lcd_implementation.h
  20. 76
      Marlin/example_configurations/Felix/Configuration.h
  21. 74
      Marlin/example_configurations/Felix/Configuration_DUAL.h
  22. 6
      Marlin/example_configurations/Felix/Configuration_adv.h
  23. 76
      Marlin/example_configurations/Hephestos/Configuration.h
  24. 6
      Marlin/example_configurations/Hephestos/Configuration_adv.h
  25. 81
      Marlin/example_configurations/K8200/Configuration.h
  26. 6
      Marlin/example_configurations/K8200/Configuration_adv.h
  27. 14
      Marlin/example_configurations/K8200/readme.md
  28. 76
      Marlin/example_configurations/SCARA/Configuration.h
  29. 6
      Marlin/example_configurations/SCARA/Configuration_adv.h
  30. 76
      Marlin/example_configurations/WITBOX/Configuration.h
  31. 6
      Marlin/example_configurations/WITBOX/Configuration_adv.h
  32. 816
      Marlin/example_configurations/delta/biv2.5/Configuration.h
  33. 552
      Marlin/example_configurations/delta/biv2.5/Configuration_adv.h
  34. 76
      Marlin/example_configurations/delta/generic/Configuration.h
  35. 6
      Marlin/example_configurations/delta/generic/Configuration_adv.h
  36. 76
      Marlin/example_configurations/delta/kossel_mini/Configuration.h
  37. 6
      Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h
  38. 77
      Marlin/example_configurations/makibox/Configuration.h
  39. 6
      Marlin/example_configurations/makibox/Configuration_adv.h
  40. 76
      Marlin/example_configurations/tvrrug/Round2/Configuration.h
  41. 6
      Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h
  42. BIN
      Marlin/fonts/ISO10646_CN.fon
  43. 22
      Marlin/fonts/README.fonts
  44. 1
      Marlin/fonts/make_fonts.bat
  45. 23
      Marlin/language.h
  46. 159
      Marlin/language_cn.h
  47. 14
      Marlin/language_de.h
  48. 2
      Marlin/language_en.h
  49. 2
      Marlin/pins.h
  50. 4
      Marlin/pins_AZTEEG_X3.h
  51. 63
      Marlin/pins_BRAINWAVE_PRO.h
  52. 2
      Marlin/pins_SAV_MKI.h
  53. 147
      Marlin/planner.cpp
  54. 14
      Marlin/planner.h
  55. 4
      Marlin/servo.cpp
  56. 6
      Marlin/servo.h
  57. 104
      Marlin/stepper.cpp
  58. 9
      Marlin/temperature.cpp
  59. 366
      Marlin/ultralcd.cpp
  60. 6
      Marlin/ultralcd.h
  61. 9
      Marlin/ultralcd_implementation_hitachi_HD44780.h
  62. 14
      Marlin/ultralcd_st7920_u8glib_rrd.h
  63. 6
      Marlin/watchdog.cpp
  64. 2
      README.md

17
Documentation/GCodes.md

@ -1,5 +1,22 @@
## Implemented G Codes
- [Movement F and M Codes](#movement-g-and-m-codes)
- [SD Card M Codes](#sd-card-m-codes)
- [Hardware Control](#hardware-control)
- [Temperature M Codes](#temperature-m-codes)
- [Message M Codes](#message-m-codes)
- [Endstops M Codes](#endstops-m-codes)
- [Special Features M Codes](#special-features-m-codes)
- [Units and Measures G and M Codes](#units-and-measures-g-and-m-codes)
- [Firmware Retraction G and M Codes](#firmware-retraction-g-and-m-codes)
- [Z Probe G and M Codes](#z-probe-g-and-m-codes)
- [Filament Diameter M Codes](#filament-diameter-m-codes)
- [EEPROM Settings M Codes](#eeprom-settings-m-codes)
- [Delta M Codes](#delta-m-codes)
- [Stepper Driver M Codes](#stepper-driver-m-codes)
- [SCARA M Codes](#scara-m-codes)
- [GCode Comments](#comments)
### Movement G and M Codes
```
G0 -> G1

206
Documentation/Hardware.md

@ -0,0 +1,206 @@
## Marlin Supported Hardware
- [Gen 7 Custom](#10-board_gen7_custom)
- [Gen 7 <=1.2](#11-board_gen7_12)
- [Gen 7 v1.3](#12-board_gen7_13)
- [Gen 7 v1.4](#13-board_gen7_14)
- [Cheaptronic v1.0](#2-board_cheaptronic)
- [Sethi 3D_1](#20-board_sethi)
- [RAMPS <=1.2](#3-board_ramps_old)
- [RAMPS 1.3 Extruder-Fan-Bed](#33-board_ramps_13_efb)
- [RAMPS 1.3 Extruder-Extruder-Bed](#34-board_ramps_13_eeb)
- [RAMPS 1.3 Extruder-Fan-Fan](#35-board_ramps_13_eff)
- [RAMPS 1.3 Extruder-Extruder-Fan](#36-board_ramps_13_eef)
- [Felix 2](#37-board_felix2)
- [Duemilanove 328P](#4-board_duemilanove_328p)
- [Gen 6](#5-board_gen6)
- [Gen 6 Deluxe](#51-board_gen6_deluxe)
- [Sanguinololu <=1.1](#6-board_sanguinololu_11)
- [Sanguinololu 1.2](#62-board_sanguinololu_12)
- [Melzi](#63-board_melzi)
- [STB v1.1](#64-board_stb_11)
- [Azteeg X1](#65-board_azteeg_x1)
- [Melzi 1284](#66-board_melzi_1284)
- [Azteeg X3](#67-board_azteeg_x3)
- [Azteeg X3 Pro](#68-board_azteeg_x3_pro)
- [Ultimaker](#7-board_ultimaker)
- [Legacy Ultimaker](#71-board_ultimaker_old)
- [Ultimainboard 2.x](#72-board_ultimain_2)
- [3DRAG](#77-board_3drag)
- [Vellemann K8200](#78-board_k8200)
- [Teensylu](#8-board_teensylu)
- [Rumba](#80-board_rumba)
- [Printrboard](#81-board_printrboard)
- [Brainwave](#82-board_brainwave)
- [SAV Mk-I](#83-board_sav_mki)
- [Teensy++2.0](#84-board_teensy2)
- [Brainwave Pro](#85-board_brainwave_pro)
- [Gen3+](#9-board_gen3_plus)
- [Gen3 Monolithic](#22-board_gen3_monolithic)
- [Megatronics](#70-board_megatronics)
- [Megatronics 2.0](#701-board_megatronics_2)
- [Minitronics 1.0](#702-board_megatronics_1)
- [Megatronics 3.0](#703-board_megatronics_3)
- [OMCA Alpha](#90-board_omca_a)
- [OMCA Final](#91-board_omca)
- [RAMBo](#301-board_rambo)
- [Elefu Ra](#21-board_elefu_3)
- [5DPrint D8](#88-board_5dprint)
- [Leapfrog](#999-board_leapfrog)
- [bq Witbox](#41-board_witbox)
- [bq Prusa i3 Hephestos](#42-board_hephestos)
- [2PrintBeta BAM&DICE](#401-board_bam_dice)
- [2PrintBeta BAM&DICE DUE](#402-board_bam_dice_due)
#### 10 BOARD_GEN7_CUSTOM
Gen7 custom (Alfons3 Version) "https://github.com/Alfons3/Generation_7_Electronics"
#### 11 BOARD_GEN7_12
Gen7 v1.1, v1.2
#### 12 BOARD_GEN7_13
Gen7 v1.3
#### 13 BOARD_GEN7_14
Gen7 v1.4
#### 2 BOARD_CHEAPTRONIC
Cheaptronic v1.0
#### 20 BOARD_SETHI
Sethi 3D_1
#### 3 BOARD_RAMPS_OLD
MEGA/RAMPS up to 1.2
#### 33 BOARD_RAMPS_13_EFB
RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed)
#### 34 BOARD_RAMPS_13_EEB
RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
#### 35 BOARD_RAMPS_13_EFF
RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Fan)
#### 36 BOARD_RAMPS_13_EEF
RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Fan)
#### 37 BOARD_FELIX2
Felix 2.0+ Electronics Board (RAMPS like)
#### 4 BOARD_DUEMILANOVE_328P
Duemilanove w/ ATMega328P pin assignments
#### 5 BOARD_GEN6
Gen6
#### 51 BOARD_GEN6_DELUXE
Gen6 deluxe
#### 6 BOARD_SANGUINOLOLU_11
Sanguinololu < 1.2
#### 62 BOARD_SANGUINOLOLU_12
Sanguinololu 1.2 and above
#### 63 BOARD_MELZI
Melzi
#### 64 BOARD_STB_11
STB V1.1
#### 65 BOARD_AZTEEG_X1
Azteeg X1
#### 66 BOARD_MELZI_1284
Melzi with ATmega1284 (MaKr3d version)
#### 67 BOARD_AZTEEG_X3
Azteeg X3
#### 68 BOARD_AZTEEG_X3_PRO
Azteeg X3 Pro
#### 7 BOARD_ULTIMAKER
Ultimaker
#### 71 BOARD_ULTIMAKER_OLD
Ultimaker (Older electronics. Pre 1.5.4. This is rare)
#### 72 BOARD_ULTIMAIN_2
Ultimainboard 2.x (Uses TEMP_SENSOR 20)
#### 77 BOARD_3DRAG
3Drag Controller
#### 78 BOARD_K8200
Vellemann K8200 Controller (derived from 3Drag Controller)
#### 8 BOARD_TEENSYLU
Teensylu
#### 80 BOARD_RUMBA
Rumba
#### 81 BOARD_PRINTRBOARD
Printrboard (AT90USB1286)
#### 82 BOARD_BRAINWAVE
Brainwave (AT90USB646)
#### 83 BOARD_SAV_MKI
SAV Mk-I (AT90USB1286)
#### 84 BOARD_TEENSY2
Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make
#### 85 BOARD_BRAINWAVE_PRO
Brainwave Pro (AT90USB1286)
#### 9 BOARD_GEN3_PLUS
Gen3+
#### 22 BOARD_GEN3_MONOLITHIC
Gen3 Monolithic Electronics
#### 70 BOARD_MEGATRONICS
Megatronics
#### 701 BOARD_MEGATRONICS_2
Megatronics v2.0
#### 702 BOARD_MEGATRONICS_1
Minitronics v1.0
#### 703 BOARD_MEGATRONICS_3
Megatronics v3.0
#### 90 BOARD_OMCA_A
Alpha OMCA board
#### 91 BOARD_OMCA
Final OMCA board
#### 301 BOARD_RAMBO
Rambo
#### 21 BOARD_ELEFU_3
Elefu Ra Board (v3)
#### 88 BOARD_5DPRINT
5DPrint D8 Driver Board
#### 999 BOARD_LEAPFROG
Leapfrog
#### 41 BOARD_WITBOX
bq WITBOX
#### 42 BOARD_HEPHESTOS
bq Prusa i3 Hephestos
#### 401 BOARD_BAM_DICE
2PrintBeta BAM&DICE with STK drivers
#### 402 BOARD_BAM_DICE_DUE
2PrintBeta BAM&DICE Due with STK drivers

9
Documentation/LCDLanguageFont.md

@ -46,11 +46,9 @@ We have two different technologies for the displays:
* nl Dutch
* ca Catalan
* eu Basque-Euskera
* cn Chinese
* jp Japanese (Katakana)
and recently on [Thingiverse](http://www.thingiverse.com/) a new port to
* jp [Japanese](http://www.thingiverse.com/thing:664397)
appeared.
## The Problem
All of this languages, except the English, normally use extended symbol sets, not contained in US-ASCII.
@ -132,6 +130,9 @@ We have two different technologies for the displays:
You'll find all translatable strings in 'language_en.h'. Please don't translate any strings from 'language.h', this may break the serial protocol.
For information about fonts see: Marlin\fonts\README.fonts
## User Instructions
Define your hardware and the wanted language in 'Configuration.h'.
To find out what charset your hardware is, define language 'test' and compile. In the menu you will see two lines from the upper half of the charset.

78
Marlin/Configuration.h

@ -41,7 +41,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -271,43 +270,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
@ -364,6 +357,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -411,17 +405,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS 200
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Mesh Bed Leveling ============================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -442,7 +439,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
// @section bedlevel
@ -641,7 +638,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
// @section lcd
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -661,10 +658,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
@ -796,8 +792,8 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define DEFAULT_NOMINAL_FILAMENT_DIA 3.0 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
#define MEASURED_UPPER_LIMIT 3.3 //upper limit factor used for sensor reading validation in mm
#define MEASURED_LOWER_LIMIT 1.9 //lower limit factor for sensor reading validation in mm
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
//defines used in the code

6
Marlin/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

4
Marlin/Makefile

@ -267,8 +267,8 @@ endif
CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \
SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp \
stepper.cpp temperature.cpp cardreader.cpp ConfigurationStore.cpp \
watchdog.cpp SPI.cpp Servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
stepper.cpp temperature.cpp cardreader.cpp configuration_store.cpp \
watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
vector_3.cpp qr_solve.cpp
ifeq ($(LIQUID_TWI2), 0)
CXXSRC += LiquidCrystal.cpp

12
Marlin/Marlin.h

@ -223,6 +223,18 @@ void Stop();
void filrunout();
#endif
/**
* Debug flags - not yet widely applied
*/
enum DebugFlags {
DEBUG_ECHO = BIT(0),
DEBUG_INFO = BIT(1),
DEBUG_ERRORS = BIT(2),
DEBUG_DRYRUN = BIT(3),
DEBUG_COMMUNICATION = BIT(4)
};
extern uint8_t marlin_debug_flags;
extern bool Running;
inline bool IsRunning() { return Running; }
inline bool IsStopped() { return !Running; }

509
Marlin/Marlin_main.cpp

File diff suppressed because it is too large

4
Marlin/SanityCheck.h

@ -87,8 +87,8 @@
/**
* Required LCD language
*/
#if !defined(DOGLCD) && defined(ULTRA_LCD) && !defined(DISPLAY_CHARSET_HD44780_JAPAN) && !defined(DISPLAY_CHARSET_HD44780_WESTERN)
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN for your LCD controller.
#if !defined(DOGLCD) && defined(ULTRA_LCD) && !defined(DISPLAY_CHARSET_HD44780_JAPAN) && !defined(DISPLAY_CHARSET_HD44780_WESTERN)&& !defined(DISPLAY_CHARSET_HD44780_CYRILLIC)
#error You must enable either DISPLAY_CHARSET_HD44780_JAPAN or DISPLAY_CHARSET_HD44780_WESTERN or DISPLAY_CHARSET_HD44780_CYRILLIC for your LCD controller.
#endif
/**

4
Marlin/BlinkM.cpp → Marlin/blinkm.cpp

@ -1,11 +1,11 @@
/*
BlinkM.cpp - Library for controlling a BlinkM over i2c
blinkm.cpp - Library for controlling a BlinkM over i2c
Created by Tim Koster, August 21 2013.
*/
#include "Marlin.h"
#ifdef BLINKM
#include "BlinkM.h"
#include "blinkm.h"
void SendColors(byte red, byte grn, byte blu) {
Wire.begin();

2
Marlin/BlinkM.h → Marlin/blinkm.h

@ -1,5 +1,5 @@
/*
BlinkM.h
blinkm.h
Library header file for BlinkM library
*/
#if ARDUINO >= 100

329
Marlin/ConfigurationStore.cpp → Marlin/configuration_store.cpp

@ -1,5 +1,5 @@
/**
* ConfigurationStore.cpp
* configuration_store.cpp
*
* Configuration and EEPROM storage
*
@ -20,72 +20,72 @@
* V19 EEPROM Layout:
*
* ver
* axis_steps_per_unit (x4)
* max_feedrate (x4)
* max_acceleration_units_per_sq_second (x4)
* acceleration
* retract_acceleration
* travel_acceleration
* minimumfeedrate
* mintravelfeedrate
* minsegmenttime
* max_xy_jerk
* max_z_jerk
* max_e_jerk
* home_offset (x3)
* M92 XYZE axis_steps_per_unit (x4)
* M203 XYZE max_feedrate (x4)
* M201 XYZE max_acceleration_units_per_sq_second (x4)
* M204 P acceleration
* M204 R retract_acceleration
* M204 T travel_acceleration
* M205 S minimumfeedrate
* M205 T mintravelfeedrate
* M205 B minsegmenttime
* M205 X max_xy_jerk
* M205 Z max_z_jerk
* M205 E max_e_jerk
* M206 XYZ home_offset (x3)
*
* Mesh bed leveling:
* active
* mesh_num_x
* mesh_num_y
* z_values[][]
* zprobe_zoffset
* M420 S active
* mesh_num_x (set in firmware)
* mesh_num_y (set in firmware)
* M421 XYZ z_values[][]
* M851 zprobe_zoffset
*
* DELTA:
* endstop_adj (x3)
* delta_radius
* delta_diagonal_rod
* delta_segments_per_second
* M666 XYZ endstop_adj (x3)
* M665 R delta_radius
* M665 L delta_diagonal_rod
* M665 S delta_segments_per_second
*
* ULTIPANEL:
* plaPreheatHotendTemp
* plaPreheatHPBTemp
* plaPreheatFanSpeed
* absPreheatHotendTemp
* absPreheatHPBTemp
* absPreheatFanSpeed
* M145 S0 H plaPreheatHotendTemp
* M145 S0 B plaPreheatHPBTemp
* M145 S0 F plaPreheatFanSpeed
* M145 S1 H absPreheatHotendTemp
* M145 S1 B absPreheatHPBTemp
* M145 S1 F absPreheatFanSpeed
*
* PIDTEMP:
* Kp[0], Ki[0], Kd[0], Kc[0]
* Kp[1], Ki[1], Kd[1], Kc[1]
* Kp[2], Ki[2], Kd[2], Kc[2]
* Kp[3], Ki[3], Kd[3], Kc[3]
* M301 E0 PIDC Kp[0], Ki[0], Kd[0], Kc[0]
* M301 E1 PIDC Kp[1], Ki[1], Kd[1], Kc[1]
* M301 E2 PIDC Kp[2], Ki[2], Kd[2], Kc[2]
* M301 E3 PIDC Kp[3], Ki[3], Kd[3], Kc[3]
*
* PIDTEMPBED:
* bedKp, bedKi, bedKd
* M304 PID bedKp, bedKi, bedKd
*
* DOGLCD:
* lcd_contrast
* M250 C lcd_contrast
*
* SCARA:
* axis_scaling (x3)
* M365 XYZ axis_scaling (x3)
*
* FWRETRACT:
* autoretract_enabled
* retract_length
* retract_length_swap
* retract_feedrate
* retract_zlift
* retract_recover_length
* retract_recover_length_swap
* retract_recover_feedrate
* M209 S autoretract_enabled
* M207 S retract_length
* M207 W retract_length_swap
* M207 F retract_feedrate
* M207 Z retract_zlift
* M208 S retract_recover_length
* M208 W retract_recover_length_swap
* M208 F retract_recover_feedrate
*
* volumetric_enabled
* M200 D volumetric_enabled (D>0 makes this enabled)
*
* filament_size (x4)
* M200 T D filament_size (x4) (T0..3)
*
* Z_DUAL_ENDSTOPS
* z_endstop_adj
* Z_DUAL_ENDSTOPS:
* M666 Z z_endstop_adj
*
*/
#include "Marlin.h"
@ -93,11 +93,11 @@
#include "planner.h"
#include "temperature.h"
#include "ultralcd.h"
#include "ConfigurationStore.h"
#include "configuration_store.h"
#ifdef MESH_BED_LEVELING
#include "mesh_bed_leveling.h"
#endif // MESH_BED_LEVELING
#endif
void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) {
uint8_t c;
@ -122,7 +122,9 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) {
#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value))
#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value))
//======================================================================================
/**
* Store Configuration Settings - M500
*/
#define DUMMY_PID_VALUE 3000.0f
@ -166,9 +168,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, mesh_num_x);
EEPROM_WRITE_VAR(i, mesh_num_y);
dummy = 0.0f;
for (int q=0; q<mesh_num_x*mesh_num_y; q++) {
EEPROM_WRITE_VAR(i, dummy);
}
for (int q=0; q<mesh_num_x*mesh_num_y; q++) EEPROM_WRITE_VAR(i, dummy);
#endif // MESH_BED_LEVELING
#ifndef ENABLE_AUTO_BED_LEVELING
@ -235,7 +235,7 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, bedKi);
EEPROM_WRITE_VAR(i, bedKd);
#ifndef DOGLCD
#ifndef HAS_LCD_CONTRAST
int lcd_contrast = 32;
#endif
EEPROM_WRITE_VAR(i, lcd_contrast);
@ -286,6 +286,10 @@ void Config_StoreSettings() {
SERIAL_ECHOLNPGM(" bytes)");
}
/**
* Retrieve Configuration Settings - M501
*/
void Config_RetrieveSettings() {
int i = EEPROM_OFFSET;
@ -319,29 +323,20 @@ void Config_RetrieveSettings() {
EEPROM_READ_VAR(i, max_e_jerk);
EEPROM_READ_VAR(i, home_offset);
uint8_t mesh_num_x = 0;
uint8_t mesh_num_y = 0;
#ifdef MESH_BED_LEVELING
EEPROM_READ_VAR(i, mbl.active);
uint8_t dummy_uint8 = 0, mesh_num_x = 0, mesh_num_y = 0;
EEPROM_READ_VAR(i, dummy_uint8);
EEPROM_READ_VAR(i, mesh_num_x);
EEPROM_READ_VAR(i, mesh_num_y);
if (mesh_num_x != MESH_NUM_X_POINTS ||
mesh_num_y != MESH_NUM_Y_POINTS) {
mbl.reset();
for (int q=0; q<mesh_num_x*mesh_num_y; q++) {
EEPROM_READ_VAR(i, dummy);
}
} else {
#ifdef MESH_BED_LEVELING
mbl.active = dummy_uint8;
if (mesh_num_x == MESH_NUM_X_POINTS && mesh_num_y == MESH_NUM_Y_POINTS) {
EEPROM_READ_VAR(i, mbl.z_values);
} else {
mbl.reset();
for (int q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
}
#else
uint8_t dummy_uint8 = 0;
EEPROM_READ_VAR(i, dummy_uint8);
EEPROM_READ_VAR(i, mesh_num_x);
EEPROM_READ_VAR(i, mesh_num_y);
for (int q=0; q<mesh_num_x*mesh_num_y; q++) {
EEPROM_READ_VAR(i, dummy);
}
for (int q = 0; q < mesh_num_x * mesh_num_y; q++) EEPROM_READ_VAR(i, dummy);
#endif // MESH_BED_LEVELING
#ifndef ENABLE_AUTO_BED_LEVELING
@ -412,7 +407,7 @@ void Config_RetrieveSettings() {
for (int q=2; q--;) EEPROM_READ_VAR(i, dummy); // bedKi, bedKd
}
#ifndef DOGLCD
#ifndef HAS_LCD_CONTRAST
int lcd_contrast;
#endif
EEPROM_READ_VAR(i, lcd_contrast);
@ -467,6 +462,10 @@ void Config_RetrieveSettings() {
#endif // EEPROM_SETTINGS
/**
* Reset Configuration Settings - M502
*/
void Config_ResetDefault() {
float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT;
float tmp2[] = DEFAULT_MAX_FEEDRATE;
@ -522,7 +521,7 @@ void Config_ResetDefault() {
absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED;
#endif
#ifdef DOGLCD
#ifdef HAS_LCD_CONTRAST
lcd_contrast = DEFAULT_LCD_CONTRAST;
#endif
@ -584,14 +583,20 @@ void Config_ResetDefault() {
#ifndef DISABLE_M503
/**
* Print Configuration Settings - M503
*/
#define CONFIG_ECHO_START do{ if (!forReplay) SERIAL_ECHO_START; }while(0)
void Config_PrintSettings(bool forReplay) {
// Always have this function, even with EEPROM_SETTINGS disabled, the current values will be shown
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Steps per unit:");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M92 X", axis_steps_per_unit[X_AXIS]);
SERIAL_ECHOPAIR(" Y", axis_steps_per_unit[Y_AXIS]);
@ -599,23 +604,23 @@ void Config_PrintSettings(bool forReplay) {
SERIAL_ECHOPAIR(" E", axis_steps_per_unit[E_AXIS]);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
#ifdef SCARA
if (!forReplay) {
SERIAL_ECHOLNPGM("Scaling factors:");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M365 X", axis_scaling[X_AXIS]);
SERIAL_ECHOPAIR(" Y", axis_scaling[Y_AXIS]);
SERIAL_ECHOPAIR(" Z", axis_scaling[Z_AXIS]);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
#endif // SCARA
if (!forReplay) {
SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M203 X", max_feedrate[X_AXIS]);
SERIAL_ECHOPAIR(" Y", max_feedrate[Y_AXIS]);
@ -623,30 +628,30 @@ void Config_PrintSettings(bool forReplay) {
SERIAL_ECHOPAIR(" E", max_feedrate[E_AXIS]);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M201 X", max_acceleration_units_per_sq_second[X_AXIS]);
SERIAL_ECHOPAIR(" Y", max_acceleration_units_per_sq_second[Y_AXIS]);
SERIAL_ECHOPAIR(" Z", max_acceleration_units_per_sq_second[Z_AXIS]);
SERIAL_ECHOPAIR(" E", max_acceleration_units_per_sq_second[E_AXIS]);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Accelerations: P=printing, R=retract and T=travel");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M204 P", acceleration);
SERIAL_ECHOPAIR(" R", retract_acceleration);
SERIAL_ECHOPAIR(" T", travel_acceleration);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s), Z=maximum Z jerk (mm/s), E=maximum E jerk (mm/s)");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M205 S", minimumfeedrate);
SERIAL_ECHOPAIR(" T", mintravelfeedrate);
@ -656,127 +661,191 @@ void Config_PrintSettings(bool forReplay) {
SERIAL_ECHOPAIR(" E", max_e_jerk);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Home offset (mm):");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M206 X", home_offset[X_AXIS]);
SERIAL_ECHOPAIR(" Y", home_offset[Y_AXIS]);
SERIAL_ECHOPAIR(" Z", home_offset[Z_AXIS]);
SERIAL_EOL;
#ifdef MESH_BED_LEVELING
if (!forReplay) {
SERIAL_ECHOLNPGM("Mesh bed leveling:");
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M420 S", (unsigned long)mbl.active);
SERIAL_ECHOPAIR(" X", (unsigned long)MESH_NUM_X_POINTS);
SERIAL_ECHOPAIR(" Y", (unsigned long)MESH_NUM_Y_POINTS);
SERIAL_EOL;
for (int y=0; y<MESH_NUM_Y_POINTS; y++) {
for (int x=0; x<MESH_NUM_X_POINTS; x++) {
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M421 X", mbl.get_x(x));
SERIAL_ECHOPAIR(" Y", mbl.get_y(y));
SERIAL_ECHOPAIR(" Z", mbl.z_values[y][x]);
SERIAL_EOL;
}
}
#endif
#ifdef DELTA
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Endstop adjustment (mm):");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M666 X", endstop_adj[X_AXIS]);
SERIAL_ECHOPAIR(" Y", endstop_adj[Y_AXIS]);
SERIAL_ECHOPAIR(" Z", endstop_adj[Z_AXIS]);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
SERIAL_ECHOLNPGM("Delta settings: L=delta_diagonal_rod, R=delta_radius, S=delta_segments_per_second");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M665 L", delta_diagonal_rod);
SERIAL_ECHOPAIR(" R", delta_radius);
SERIAL_ECHOPAIR(" S", delta_segments_per_second);
SERIAL_EOL;
#elif defined(Z_DUAL_ENDSTOPS)
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Z2 Endstop adjustment (mm):");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M666 Z", z_endstop_adj);
SERIAL_EOL;
#endif // DELTA
#ifdef ULTIPANEL
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Material heatup parameters:");
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M145 M0 H", (unsigned long)plaPreheatHotendTemp);
SERIAL_ECHOPAIR(" B", (unsigned long)plaPreheatHPBTemp);
SERIAL_ECHOPAIR(" F", (unsigned long)plaPreheatFanSpeed);
SERIAL_EOL;
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M145 M1 H", (unsigned long)absPreheatHotendTemp);
SERIAL_ECHOPAIR(" B", (unsigned long)absPreheatHPBTemp);
SERIAL_ECHOPAIR(" F", (unsigned long)absPreheatFanSpeed);
SERIAL_EOL;
#endif // ULTIPANEL
#if defined(PIDTEMP) || defined(PIDTEMPBED)
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("PID settings:");
SERIAL_ECHO_START;
}
#if defined(PIDTEMP) && defined(PIDTEMPBED)
SERIAL_EOL;
#endif
#ifdef PIDTEMP
SERIAL_ECHOPAIR(" M301 P", PID_PARAM(Kp, 0)); // for compatibility with hosts, only echos values for E0
#if EXTRUDERS > 1
if (forReplay) {
for (uint8_t i = 0; i < EXTRUDERS; i++) {
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M301 E", (unsigned long)i);
SERIAL_ECHOPAIR(" P", PID_PARAM(Kp, i));
SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, i)));
SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, i)));
#ifdef PID_ADD_EXTRUSION_RATE
SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, i));
#endif
SERIAL_EOL;
}
}
else
#endif // EXTRUDERS > 1
// !forReplay || EXTRUDERS == 1
{
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M301 P", PID_PARAM(Kp, 0)); // for compatibility with hosts, only echo values for E0
SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, 0)));
SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, 0)));
SERIAL_EOL;
#ifdef PID_ADD_EXTRUSION_RATE
SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, 0));
#endif
SERIAL_EOL;
}
#endif // PIDTEMP
#ifdef PIDTEMPBED
SERIAL_ECHOPAIR(" M304 P", bedKp); // for compatibility with hosts, only echos values for E0
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M304 P", bedKp);
SERIAL_ECHOPAIR(" I", unscalePID_i(bedKi));
SERIAL_ECHOPAIR(" D", unscalePID_d(bedKd));
SERIAL_EOL;
#endif
#endif // PIDTEMP || PIDTEMPBED
#ifdef HAS_LCD_CONTRAST
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("LCD Contrast:");
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M250 C", (unsigned long)lcd_contrast);
SERIAL_EOL;
#endif
#ifdef FWRETRACT
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Retract: S=Length (mm) F:Speed (mm/m) Z: ZLift (mm)");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M207 S", retract_length);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" W", retract_length_swap);
#endif
SERIAL_ECHOPAIR(" F", retract_feedrate*60);
SERIAL_ECHOPAIR(" Z", retract_zlift);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Recover: S=Extra length (mm) F:Speed (mm/m)");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M208 S", retract_recover_length);
#if EXTRUDERS > 1
SERIAL_ECHOPAIR(" W", retract_recover_length_swap);
#endif
SERIAL_ECHOPAIR(" F", retract_recover_feedrate*60);
SERIAL_EOL;
SERIAL_ECHO_START;
CONFIG_ECHO_START;
if (!forReplay) {
SERIAL_ECHOLNPGM("Auto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries");
SERIAL_ECHO_START;
CONFIG_ECHO_START;
}
SERIAL_ECHOPAIR(" M209 S", (unsigned long)(autoretract_enabled ? 1 : 0));
SERIAL_EOL;
#if EXTRUDERS > 1
if (!forReplay) {
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Multi-extruder settings:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" Swap retract length (mm): ", retract_length_swap);
SERIAL_EOL;
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" Swap rec. addl. length (mm): ", retract_recover_length_swap);
SERIAL_EOL;
}
#endif // EXTRUDERS > 1
#endif // FWRETRACT
SERIAL_ECHO_START;
if (volumetric_enabled) {
if (!forReplay) {
CONFIG_ECHO_START;
SERIAL_ECHOLNPGM("Filament settings:");
SERIAL_ECHO_START;
}
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M200 D", filament_size[0]);
SERIAL_EOL;
#if EXTRUDERS > 1
SERIAL_ECHO_START;
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M200 T1 D", filament_size[1]);
SERIAL_EOL;
#if EXTRUDERS > 2
SERIAL_ECHO_START;
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M200 T2 D", filament_size[2]);
SERIAL_EOL;
#if EXTRUDERS > 3
SERIAL_ECHO_START;
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M200 T3 D", filament_size[3]);
SERIAL_EOL;
#endif
@ -785,21 +854,23 @@ void Config_PrintSettings(bool forReplay) {
} else {
if (!forReplay) {
CONFIG_ECHO_START;
SERIAL_ECHOLNPGM("Filament settings: Disabled");
}
}
#ifdef ENABLE_AUTO_BED_LEVELING
SERIAL_ECHO_START;
#ifdef CUSTOM_M_CODES
if (!forReplay) {
CONFIG_ECHO_START;
SERIAL_ECHOLNPGM("Z-Probe Offset (mm):");
SERIAL_ECHO_START;
}
CONFIG_ECHO_START;
SERIAL_ECHOPAIR(" M", (unsigned long)CUSTOM_M_CODE_SET_Z_PROBE_OFFSET);
SERIAL_ECHOPAIR(" Z", -zprobe_zoffset);
#else
if (!forReplay) {
CONFIG_ECHO_START;
SERIAL_ECHOPAIR("Z-Probe Offset (mm):", -zprobe_zoffset);
}
#endif

6
Marlin/ConfigurationStore.h → Marlin/configuration_store.h

@ -1,5 +1,5 @@
#ifndef CONFIGURATIONSTORE_H
#define CONFIGURATIONSTORE_H
#ifndef CONFIGURATION_STORE_H
#define CONFIGURATION_STORE_H
#include "Configuration.h"
@ -19,4 +19,4 @@ void Config_ResetDefault();
FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); }
#endif
#endif //CONFIGURATIONSTORE_H
#endif //CONFIGURATION_STORE_H

74
Marlin/configurator/config/Configuration.h

@ -41,7 +41,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -271,44 +270,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -364,6 +356,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -411,17 +404,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS 200
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -442,7 +438,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
// @section bedlevel
@ -640,7 +636,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
// @section lcd
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -660,9 +656,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/configurator/config/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

25
Marlin/configurator/config/language.h

@ -30,6 +30,7 @@
// eu Basque-Euskera
// kana Japanese
// kana_utf Japanese
// cn Chinese
#ifndef LANGUAGE_INCLUDE
// pick your language from the list above
@ -70,7 +71,7 @@
#endif
#else
#ifndef MACHINE_NAME
#define MACHINE_NAME "Mendel"
#define MACHINE_NAME "3D Printer"
#endif
#endif
@ -129,13 +130,15 @@
#define MSG_FILE_PRINTED "Done printing file"
#define MSG_BEGIN_FILE_LIST "Begin file list"
#define MSG_END_FILE_LIST "End file list"
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
#define MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
#define MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
#define MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
#define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_M104_INVALID_EXTRUDER "M104 " MSG_INVALID_EXTRUDER " "
#define MSG_M105_INVALID_EXTRUDER "M105 " MSG_INVALID_EXTRUDER " "
#define MSG_M109_INVALID_EXTRUDER "M109 " MSG_INVALID_EXTRUDER " "
#define MSG_M200_INVALID_EXTRUDER "M200 " MSG_INVALID_EXTRUDER " "
#define MSG_M218_INVALID_EXTRUDER "M218 " MSG_INVALID_EXTRUDER " "
#define MSG_M221_INVALID_EXTRUDER "M221 " MSG_INVALID_EXTRUDER " "
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
#define MSG_HEATING "Heating..."
#define MSG_HEATING_COMPLETE "Heating done."
#define MSG_BED_HEATING "Bed Heating."
@ -147,8 +150,6 @@
#define MSG_RESEND "Resend: "
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
#define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_X_MIN "x_min: "
#define MSG_X_MAX "x_max: "
#define MSG_Y_MIN "y_min: "
@ -157,6 +158,10 @@
#define MSG_Z_MAX "z_max: "
#define MSG_Z2_MAX "z2_max: "
#define MSG_Z_PROBE "z_probe: "
#define MSG_ERR_MATERIAL_INDEX "M145 S<index> out of range (0-1)"
#define MSG_ERR_M421_REQUIRES_XYZ "M421 requires XYZ parameters"
#define MSG_ERR_MESH_INDEX_OOB "Mesh XY index is out of bounds"
#define MSG_ERR_M428_TOO_FAR "Too far from reference point"
#define MSG_M119_REPORT "Reporting endstop status"
#define MSG_ENDSTOP_HIT "TRIGGERED"
#define MSG_ENDSTOP_OPEN "open"
@ -209,7 +214,7 @@
#define MSG_OK_B "ok B:"
#define MSG_OK_T "ok T:"
#define MSG_AT " @:"
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from above into Configuration.h"
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
#define MSG_PID_DEBUG " PID_DEBUG "
#define MSG_PID_DEBUG_INPUT ": Input "
#define MSG_PID_DEBUG_OUTPUT " Output "

0
Marlin/DOGMbitmaps.h → Marlin/dogm_bitmaps.h

270
Marlin/dogm_font_data_ISO10646_CN.h

@ -0,0 +1,270 @@
/*
Fontname: ISO10646_CN
Copyright: A. Hardtung, public domain
Capital A Height: 7, '1' Height: 7
Calculated Max Values w=11 h=11 x= 2 y=10 dx=12 dy= 0 ascent=10 len=22
Font Bounding box w=12 h=11 x= 0 y=-2
Calculated Min Values x= 0 y=-1 dx= 0 dy= 0
Pure Font ascent = 7 descent=-1
X Font ascent = 7 descent=-1
Max Font ascent =10 descent=-1
*/
#include <utility/u8g.h>
const u8g_fntpgm_uint8_t ISO10646_CN[4105] U8G_SECTION(".progmem.ISO10646_CN") = {
0,12,11,0,254,7,1,146,3,33,32,255,255,10,255,7,
255,0,0,0,6,0,10,1,7,7,6,2,0,128,128,128,
128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6,
0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32,
120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32,
64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104,
2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32,
64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32,
32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5,
5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192,
64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192,
192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6,
0,0,112,136,152,168,200,136,112,3,7,7,6,1,0,64,
192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112,
128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240,
5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7,
6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0,
112,128,128,240,136,136,112,5,7,7,6,0,0,248,8,16,
32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136,
112,5,7,7,6,0,0,112,136,136,120,8,8,112,2,5,
5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192,
192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64,
32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,0,
0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136,
8,16,32,0,32,5,7,7,6,0,0,112,136,8,104,168,
168,112,5,7,7,6,0,0,112,136,136,248,136,136,136,5,
7,7,6,0,0,240,136,136,240,136,136,240,5,7,7,6,
0,0,112,136,128,128,128,136,112,5,7,7,6,0,0,240,
136,136,136,136,136,240,5,7,7,6,0,0,248,128,128,240,
128,128,248,5,7,7,6,0,0,248,128,128,240,128,128,128,
5,7,7,6,0,0,112,136,128,184,136,136,112,5,7,7,
6,0,0,136,136,136,248,136,136,136,1,7,7,6,2,0,
128,128,128,128,128,128,128,5,7,7,6,0,0,56,16,16,
16,16,144,96,5,7,7,6,0,0,136,144,160,192,160,144,
136,5,7,7,6,0,0,128,128,128,128,128,128,248,5,7,
7,6,0,0,136,216,168,136,136,136,136,5,7,7,6,0,
0,136,136,200,168,152,136,136,5,7,7,6,0,0,112,136,
136,136,136,136,112,5,7,7,6,0,0,240,136,136,240,128,
128,128,5,7,7,6,0,0,112,136,136,136,168,144,104,5,
7,7,6,0,0,240,136,136,240,160,144,136,5,7,7,6,
0,0,120,128,128,112,8,8,240,5,7,7,6,0,0,248,
32,32,32,32,32,32,5,7,7,6,0,0,136,136,136,136,
136,136,112,5,7,7,6,0,0,136,136,136,136,136,80,32,
5,7,7,6,0,0,136,136,136,136,136,168,80,5,7,7,
6,0,0,136,136,80,32,80,136,136,5,7,7,6,0,0,
136,136,136,80,32,32,32,5,7,7,6,0,0,248,8,16,
32,64,128,248,3,7,7,6,0,0,224,128,128,128,128,128,
224,5,5,5,6,0,1,128,64,32,16,8,3,7,7,6,
0,0,224,32,32,32,32,32,224,5,3,3,6,0,4,32,
80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,128,
64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,6,
0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,112,
128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,136,
120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,6,
0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,112,
136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,136,
136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,3,
8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,7,
6,1,0,128,128,144,160,192,160,144,3,7,7,6,1,0,
192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,168,
168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,5,
6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,136,
136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,8,
5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,0,
0,112,128,112,8,240,4,7,7,6,0,0,64,64,224,64,
64,64,48,5,5,5,6,0,0,136,136,136,152,104,5,5,
5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,136,
136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,5,
6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,0,
0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,128,
64,64,32,1,7,7,6,2,0,128,128,128,128,128,128,128,
3,7,7,6,1,0,128,64,64,32,64,64,128,5,2,2,
6,0,3,104,144,0,0,0,6,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,0,0,0,12,0,10,0,
0,0,12,0,10,0,0,0,12,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,0,0,0,12,0,10,0,
0,0,12,0,10,0,0,0,12,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,0,0,0,12,0,10,0,
0,0,12,0,10,0,0,0,12,0,10,0,0,0,12,0,
10,0,0,0,12,0,10,0,0,0,12,0,10,0,0,0,
12,0,10,0,0,0,12,0,10,11,11,22,12,0,255,255,
224,2,0,2,0,4,0,13,0,20,128,36,64,196,32,4,
0,4,0,4,0,11,11,22,12,0,255,249,0,138,0,171,
224,172,64,170,64,170,64,170,64,170,128,33,0,82,128,140,
96,11,11,22,12,0,255,36,0,36,0,63,128,68,0,132,
0,4,0,255,224,10,0,17,0,32,128,192,96,11,11,22,
12,0,255,36,0,36,0,63,192,68,0,4,0,255,224,9,
0,9,0,17,32,33,32,64,224,11,11,22,12,0,255,32,
0,61,224,81,32,145,32,17,32,255,32,17,32,41,32,37,
224,69,32,128,0,11,11,22,12,0,255,32,128,127,192,8,
64,255,224,17,0,32,128,95,64,128,32,63,128,0,0,127,
192,11,11,22,12,0,255,34,64,71,224,148,128,228,128,47,
224,68,128,244,128,7,224,52,128,196,128,7,224,11,11,22,
12,0,255,4,128,143,224,73,0,25,0,47,192,9,0,9,
0,47,192,73,0,137,0,15,224,11,11,22,12,0,255,16,
0,63,128,81,0,14,0,49,128,192,96,63,128,36,128,63,
128,36,128,63,128,11,11,22,12,0,255,34,128,250,64,7,
224,250,128,138,128,138,128,250,128,34,128,178,128,170,160,100,
224,11,11,22,12,0,255,34,32,71,64,146,128,239,224,34,
0,71,192,236,64,7,192,52,64,199,192,4,64,11,11,22,
12,0,255,8,0,15,192,8,0,8,0,255,224,8,0,14,
0,9,128,8,64,8,0,8,0,10,11,22,12,0,255,255,
128,0,128,0,128,128,128,128,128,255,128,128,0,128,0,128,
64,128,64,127,192,11,11,22,12,0,255,71,192,65,0,239,
224,65,0,69,0,105,96,201,32,77,96,73,32,79,224,200,
32,11,11,22,12,0,255,8,0,4,0,4,0,10,0,10,
0,10,0,17,0,17,0,32,128,64,64,128,32,11,11,22,
12,0,255,34,64,34,0,247,224,34,0,35,224,53,32,229,
32,37,64,40,128,41,64,114,32,11,10,20,12,0,0,68,
64,68,64,68,64,127,192,4,0,4,0,132,32,132,32,132,
32,255,224,11,11,22,12,0,255,4,0,0,0,127,192,4,
0,4,0,4,0,127,192,4,0,4,0,4,0,255,224,11,
11,22,12,0,255,255,224,17,0,1,192,254,0,72,128,37,
0,4,0,255,224,21,0,36,128,196,96,11,11,22,12,0,
255,17,0,127,192,68,64,127,192,68,64,127,192,4,0,255,
224,4,0,4,0,4,0,9,11,22,12,0,255,16,0,255,
128,128,128,128,128,255,128,128,128,128,128,255,128,128,128,128,
128,255,128,11,11,22,12,0,255,113,0,1,0,3,224,249,
32,33,32,65,32,81,32,137,32,250,32,2,32,4,192,11,
11,22,12,0,255,127,192,17,0,17,0,17,0,17,0,255,
224,17,0,17,0,33,0,33,0,65,0,11,11,22,12,0,
255,33,0,34,0,244,64,87,224,80,32,87,192,148,64,84,
64,36,64,87,192,148,64,11,11,22,12,0,255,17,0,10,
0,127,192,4,0,4,0,255,224,4,0,10,0,17,0,32,
128,192,96,10,11,22,12,0,255,95,192,0,64,132,64,132,
64,191,64,132,64,140,64,148,64,164,64,140,64,129,192,11,
11,22,12,0,255,36,0,39,192,36,0,36,0,255,224,0,
0,20,64,36,128,71,0,12,0,112,0,11,11,22,12,0,
255,36,128,4,128,15,192,228,128,36,128,63,224,36,128,36,
128,40,128,80,0,143,224,11,11,22,12,0,255,8,0,8,
0,255,128,136,128,136,128,255,128,136,128,136,128,255,160,136,
32,7,224,11,11,22,12,0,255,39,128,36,128,244,128,36,
128,116,128,108,128,164,128,36,128,36,160,40,160,48,96,10,
11,22,12,0,255,255,192,128,64,128,64,158,64,146,64,146,
64,158,64,128,64,128,64,255,192,128,64,11,11,22,12,0,
255,127,192,68,0,95,192,80,64,95,192,80,64,95,192,66,
0,74,128,82,64,166,32,11,11,22,12,0,255,4,0,7,
224,4,0,127,192,64,64,64,64,64,64,127,192,0,0,82,
64,137,32,11,11,22,12,0,255,71,128,36,128,4,128,4,
128,232,96,32,0,47,192,36,64,34,128,49,0,38,192,11,
11,22,12,0,255,127,192,74,64,127,192,4,0,255,224,4,
0,63,128,32,128,36,128,36,128,255,224,11,11,22,12,0,
255,34,0,79,224,72,32,79,224,200,0,79,224,74,160,90,
160,111,224,74,160,72,96,11,11,22,12,0,255,243,192,36,
64,42,128,241,0,34,128,101,224,114,32,165,64,32,128,35,
0,44,0,11,11,22,12,0,255,4,0,255,224,128,32,0,
0,255,224,4,0,36,0,39,192,36,0,84,0,143,224,11,
11,22,12,0,255,115,224,16,128,81,0,35,224,250,32,42,
160,34,160,34,160,32,128,33,64,98,32,11,11,22,12,0,
255,34,0,247,128,34,128,54,128,226,160,37,160,36,96,104,
32,0,0,82,64,137,32,11,11,22,12,0,255,115,192,66,
0,66,0,123,224,74,64,74,64,122,64,74,64,66,64,68,
64,136,64,11,11,22,12,0,255,8,0,255,224,8,0,31,
192,48,64,95,192,144,64,31,192,16,64,16,64,16,192,11,
11,22,12,0,255,2,0,127,224,66,0,66,0,95,192,66,
0,71,0,74,128,82,64,98,32,130,0,11,11,22,12,0,
255,243,192,150,64,145,128,166,96,161,0,151,192,145,0,149,
0,231,224,129,0,129,0,11,11,22,12,0,255,15,128,136,
128,79,128,8,128,143,128,64,0,31,192,53,64,85,64,149,
64,63,224,11,11,22,12,0,255,39,224,32,128,248,128,32,
128,32,128,56,128,224,128,32,128,32,128,32,128,97,128,11,
11,22,12,0,255,31,224,145,0,87,192,20,64,23,192,148,
64,87,192,17,0,85,64,153,32,35,0,11,11,22,12,0,
255,32,128,39,224,242,64,33,128,34,64,52,32,226,64,34,
64,34,64,34,64,100,64,11,11,22,12,0,255,65,0,65,
0,79,224,233,32,73,32,73,32,111,224,201,32,73,32,73,
32,207,224,11,11,22,12,0,255,33,0,241,0,79,224,169,
32,249,32,47,224,57,32,233,32,41,32,47,224,40,32,11,
11,22,12,0,255,143,224,73,32,9,32,203,160,73,32,79,
224,72,32,75,160,74,160,107,160,80,224,11,11,22,12,0,
255,127,192,4,0,68,64,36,64,36,128,4,0,255,224,4,
0,4,0,4,0,4,0,11,11,22,12,0,255,130,0,66,
0,31,224,194,0,95,192,82,64,95,192,71,0,74,128,82,
64,191,224,11,11,22,12,0,255,4,0,127,224,72,128,127,
224,72,128,79,128,64,0,95,192,72,64,71,128,152,96,11,
11,22,12,0,255,1,0,239,224,161,0,164,64,175,224,164,
64,175,224,169,32,233,32,2,128,12,96,11,11,22,12,0,
255,20,192,246,160,188,96,167,128,168,128,191,224,169,32,239,
224,9,32,15,224,9,32,11,11,22,12,0,255,127,128,64,
128,66,128,98,128,84,128,72,128,72,128,84,160,98,160,64,
96,128,32,11,11,22,12,0,255,4,0,127,224,64,32,127,
224,64,0,125,224,84,32,76,160,84,96,100,160,141,96,11,
11,22,12,0,255,130,0,95,224,4,0,8,64,159,224,64,
32,10,128,10,128,74,160,146,160,34,96,11,11,22,12,0,
255,65,0,79,224,232,32,66,128,68,64,104,32,199,192,65,
0,65,0,65,0,207,224,11,11,22,12,0,255,80,32,125,
32,145,32,255,32,17,32,125,32,85,32,85,32,84,32,92,
32,16,224,11,11,22,12,0,255,63,128,32,128,63,128,32,
128,255,224,72,0,123,192,73,64,121,64,72,128,251,96,11,
11,22,12,0,255,4,0,4,0,4,0,36,128,36,64,68,
64,68,32,132,32,4,0,4,0,28,0,11,11,22,12,0,
255,4,0,4,0,4,0,255,224,4,0,10,0,10,0,17,
0,17,0,32,128,192,96,9,10,20,10,0,0,136,128,73,
0,8,0,255,128,0,128,0,128,127,128,0,128,0,128,255,
128,11,11,22,12,0,255,33,0,18,0,255,224,0,0,120,
128,74,128,122,128,74,128,122,128,72,128,89,128,11,11,22,
12,0,255,39,192,0,0,0,0,239,224,33,0,34,0,36,
64,47,224,32,32,80,0,143,224,11,11,22,12,0,255,32,
128,39,0,249,0,33,192,119,0,33,0,249,224,39,0,113,
32,169,32,32,224,11,11,22,12,0,255,16,64,16,64,253,
224,16,64,56,192,53,64,82,64,148,64,16,64,16,64,16,
192,11,11,22,12,0,255,0,64,248,64,11,224,8,64,136,
64,82,64,81,64,33,64,80,64,72,64,137,192,10,11,22,
12,0,255,132,0,132,64,132,128,245,0,134,0,132,0,132,
0,148,0,164,64,196,64,131,192,11,11,22,12,0,255,17,
32,125,0,17,0,255,224,41,0,253,64,73,64,124,128,8,
160,253,96,10,32,11,11,22,12,0,255,23,192,36,64,36,
64,103,192,161,0,47,224,33,0,35,128,37,64,41,32,33,
0,11,11,22,12,0,255,8,0,255,224,16,0,39,192,32,
128,97,0,175,224,33,0,33,0,33,0,35,0,11,11,22,
12,0,255,36,0,47,224,180,0,164,128,164,160,170,192,42,
128,40,128,41,64,50,64,36,32,11,11,22,12,0,255,127,
224,128,0,63,192,32,64,63,192,16,0,31,192,16,64,40,
128,71,0,56,224,11,11,22,12,0,255,127,224,64,0,64,
0,64,0,64,0,64,0,64,0,64,0,64,0,64,0,128,
0,11,11,22,12,0,255,255,224,4,0,127,192,68,64,127,
192,68,64,127,192,68,0,36,0,24,0,231,224,11,11,22,
12,0,255,17,224,253,0,69,0,41,224,253,64,17,64,125,
64,17,64,85,64,146,64,52,64,11,11,22,12,0,255,33,
0,95,224,64,0,207,192,64,0,79,192,64,0,79,192,72,
64,79,192,72,64,11,11,22,12,0,255,4,0,127,192,64,
64,127,192,64,64,127,192,64,64,127,192,4,64,82,32,191,
160,11,11,22,12,0,255,127,192,68,64,127,192,68,64,127,
192,4,0,27,0,224,224,17,0,17,0,97,0,11,11,22,
12,0,255,255,224,4,0,8,0,127,224,73,32,79,32,73,
32,79,32,73,32,73,32,127,224,11,11,22,12,0,255,253,
224,86,64,121,64,56,128,85,64,146,32,255,224,4,0,39,
192,36,0,255,224,11,11,22,12,0,255,251,128,82,0,123,
224,18,64,250,64,20,64,63,128,32,128,63,128,32,128,63,
128,11,11,22,12,0,255,31,224,32,0,39,192,100,64,167,
192,32,0,47,224,40,32,39,192,33,0,35,0,11,11,22,
12,0,255,243,224,130,32,130,32,250,32,130,32,130,32,138,
32,178,32,194,224,2,0,2,0,11,11,22,12,0,255,36,
128,70,160,149,192,228,128,39,224,68,128,245,192,6,160,52,
128,196,128,7,224,11,11,22,12,0,255,39,192,65,0,135,
224,224,32,34,128,69,128,242,128,15,224,48,128,193,64,2,
32,11,11,22,12,0,255,2,0,2,0,34,0,35,192,34,
0,34,0,34,0,34,0,34,0,34,0,255,224,9,11,22,
12,0,255,8,0,8,0,255,128,136,128,136,128,136,128,255,
128,136,128,136,128,136,128,255,128,11,11,22,12,0,255,33,
0,83,160,65,0,247,224,81,0,83,192,86,64,83,192,90,
64,83,192,66,64,11,11,22,12,0,255,127,192,4,0,4,
0,4,0,255,224,10,0,10,0,18,0,34,32,66,32,129,
224,11,11,22,12,0,255,17,0,33,0,47,224,97,0,163,
128,35,128,37,64,37,64,41,32,33,0,33,0,11,11,22,
12,0,255,247,224,148,32,244,32,151,224,148,128,244,128,151,
224,148,128,244,160,150,96,4,32,11,11,22,12,0,255,123,
224,148,128,4,0,127,192,4,0,255,224,1,0,255,224,33,
0,17,0,7,0,11,11,22,12,0,255,33,0,71,192,145,
0,47,224,96,128,175,224,32,128,36,128,34,128,32,128,35,
128,11,11,22,12,0,255,39,192,36,64,247,192,46,224,42,
160,62,224,225,0,47,224,35,128,37,64,105,32,11,11,22,
12,0,255,20,0,39,224,42,0,98,0,163,192,34,0,34,
0,35,224,34,0,34,0,34,0};

42
Marlin/dogm_lcd_implementation.h

@ -29,7 +29,7 @@
#endif
#include <U8glib.h>
#include "DOGMbitmaps.h"
#include "dogm_bitmaps.h"
#include "ultralcd.h"
#include "ultralcd_st7920_u8glib_rrd.h"
@ -64,6 +64,10 @@
#elif defined( DISPLAY_CHARSET_ISO10646_KANA )
#include "dogm_font_data_ISO10646_Kana.h"
#define FONT_MENU_NAME ISO10646_Kana_5x7
#elif defined( DISPLAY_CHARSET_ISO10646_CN )
#include "dogm_font_data_ISO10646_CN.h"
#define FONT_MENU_NAME ISO10646_CN
#define TALL_FONT_CORRECTION 1
#else // fall-back
#include "dogm_font_data_ISO10646_1.h"
#define FONT_MENU_NAME ISO10646_1_5x7
@ -106,6 +110,10 @@
#define LCD_WIDTH_EDIT 22
#endif
#ifndef TALL_FONT_CORRECTION
#define TALL_FONT_CORRECTION 0
#endif
#define START_ROW 0
// LCD selection
@ -123,6 +131,13 @@
U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0
#endif
#ifndef LCD_PIXEL_WIDTH
#define LCD_PIXEL_WIDTH 128
#endif
#ifndef LCD_PIXEL_HEIGHT
#define LCD_PIXEL_HEIGHT 64
#endif
#include "utf_mapper.h"
int lcd_contrast;
@ -172,6 +187,7 @@ char lcd_printPGM(const char* str) {
static bool show_splashscreen = true;
/* Warning: This function is called from interrupt context */
static void lcd_implementation_init() {
#ifdef LCD_PIN_BL // Enable LCD backlight
@ -252,20 +268,21 @@ static void lcd_implementation_status_screen() {
#ifdef SDSUPPORT
// SD Card Symbol
u8g.drawBox(42,42,8,7);
u8g.drawBox(50,44,2,5);
u8g.drawFrame(42,49,10,4);
u8g.drawPixel(50,43);
u8g.drawBox(42, 42 - TALL_FONT_CORRECTION, 8, 7);
u8g.drawBox(50, 44 - TALL_FONT_CORRECTION, 2, 5);
u8g.drawFrame(42, 49 - TALL_FONT_CORRECTION, 10, 4);
u8g.drawPixel(50, 43 - TALL_FONT_CORRECTION);
// Progress bar frame
u8g.drawFrame(54,49,73,4);
u8g.drawFrame(54, 49, 73, 4 - TALL_FONT_CORRECTION);
// SD Card Progress bar and clock
lcd_setFont(FONT_STATUSMENU);
if (IS_SD_PRINTING) {
// Progress bar solid part
u8g.drawBox(55, 50, (unsigned int)(71.f * card.percentDone() / 100.f), 2);
u8g.drawBox(55, 50, (unsigned int)(71.f * card.percentDone() / 100.f), 2 - TALL_FONT_CORRECTION);
}
u8g.setPrintPos(80,48);
@ -306,9 +323,9 @@ static void lcd_implementation_status_screen() {
lcd_setFont(FONT_STATUSMENU);
#ifdef USE_SMALL_INFOFONT
u8g.drawBox(0,30,128,10);
u8g.drawBox(0,30,LCD_PIXEL_WIDTH,10);
#else
u8g.drawBox(0,30,128,9);
u8g.drawBox(0,30,LCD_PIXEL_WIDTH,9);
#endif
u8g.setColorIndex(0); // white on black
u8g.setPrintPos(2,XYZ_BASELINE);
@ -366,7 +383,7 @@ static void lcd_implementation_status_screen() {
static void lcd_implementation_mark_as_selected(uint8_t row, bool isSelected) {
if (isSelected) {
u8g.setColorIndex(1); // black on white
u8g.drawBox(0, row * DOG_CHAR_HEIGHT + 3, 128, DOG_CHAR_HEIGHT);
u8g.drawBox(0, row * DOG_CHAR_HEIGHT + 3 - TALL_FONT_CORRECTION, LCD_PIXEL_WIDTH, DOG_CHAR_HEIGHT);
u8g.setColorIndex(0); // following text must be white on black
}
else {
@ -386,13 +403,15 @@ static void lcd_implementation_drawmenu_generic(bool isSelected, uint8_t row, co
pstr++;
}
while (n--) lcd_print(' ');
u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT);
lcd_print(post_char);
lcd_print(' ');
}
static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const char* pstr, const char* data, bool pgm) {
char c;
uint8_t n = LCD_WIDTH - 2 - (pgm ? lcd_strlen_P(data) : (lcd_strlen((char*)data)));
uint8_t vallen = (pgm ? lcd_strlen_P(data) : (lcd_strlen((char*)data)));
uint8_t n = LCD_WIDTH - 2 - vallen;
lcd_implementation_mark_as_selected(row, isSelected);
@ -402,6 +421,7 @@ static void _drawmenu_setting_edit_generic(bool isSelected, uint8_t row, const c
}
lcd_print(':');
while (n--) lcd_print(' ');
u8g.setPrintPos(LCD_PIXEL_WIDTH - DOG_CHAR_WIDTH * vallen, (row + 1) * DOG_CHAR_HEIGHT);
if (pgm) { lcd_printPGM(data); } else { lcd_print((char *)data); }
}

76
Marlin/example_configurations/Felix/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -237,44 +236,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -317,6 +309,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -350,17 +343,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS 235
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -381,7 +377,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -574,7 +570,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -594,9 +590,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

74
Marlin/example_configurations/Felix/Configuration_DUAL.h

@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -237,44 +236,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -317,6 +309,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -350,17 +343,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS 235
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -377,7 +373,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -570,7 +566,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -590,9 +586,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/Felix/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

76
Marlin/example_configurations/Hephestos/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(bq Hephestos)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -258,44 +257,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -338,6 +330,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -371,17 +364,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define Z_MAX_POS 180
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -402,7 +398,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -594,7 +590,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -614,9 +610,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/Hephestos/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

81
Marlin/example_configurations/K8200/Configuration.h

@ -1,4 +1,9 @@
#ifndef CONFIGURATION_H
// Example configuration file for Vellemann K8200
// tested on K8200 with VM8201 (Display)
// and Arduino 1.6.1 (Win) by @CONSULitAS, 2015-04-14
// https://github.com/CONSULitAS/Marlin-K8200/archive/K8200_stable_2015-04-14.zip
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -41,7 +46,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(K8200, CONSULitAS)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -282,44 +286,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -375,6 +372,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z true
@ -422,17 +420,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS 200
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Mesh Bed Leveling ============================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -453,7 +454,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
// @section bedlevel
@ -652,7 +653,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
// @section lcd
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -672,9 +673,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
#define ULTIMAKERCONTROLLER // K8200: for Display VM8201 // as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/K8200/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

14
Marlin/example_configurations/K8200/readme.md

@ -1,5 +1,5 @@
# Example Configuration for Vellemann K8200
* Configuration files for **Vellemann K8200** (with VM8201 - LCD Option for K8200)
# Example Configuration for Vellemann [K8200](http://www.k8200.eu/)
* Configuration files for **Vellemann K8200** (with [VM8201](http://www.vellemanprojects.eu/products/view/?id=416158) - LCD Option for K8200)
* K8200 is a 3Drag clone - configuration should work with 3Drag http://reprap.org/wiki/3drag, too. Please report.
* updated manually with parameters from genuine Vellemann Firmware "firmware_k8200_marlinv2" based on the recent development branch
@ -7,14 +7,14 @@
* VM8201 uses "DISPLAY_CHARSET_HD44870_JAPAN" and "ULTIMAKERCONTROLLER"
* german (de) translation with umlaut is supported now - thanks to @AnHardt for the great hardware based umlaut support
I (@CONSULitAS) tested the changes on my K8200 with 20x4-LCD and Arduino 1.0.5 for Windows (SD library added to IDE manually) - everything works well.
I [@CONSULitAS](https://github.com/CONSULitAS) tested the changes on my K8200 with 20x4-LCD and Arduino 1.6.1 for Windows (SD library added to IDE manually) - everything works well.
**Source for genuine Vellemann Firmware V2 (with LCD/SD-Support):**
* [firmware_k8200_v2.1.1.zip](http://www.k8200.eu/downloads/files/downloads/firmware_k8200_v2.1.1.zip)
**Source for genuine [Vellemann Firmware](http://www.k8200.eu/support/downloads/)**
* V2.1.1 (for z axis upgrade, date branched: 2013-06-05): [firmware_k8200_v2.1.1.zip](http://www.k8200.eu/downloads/files/downloads/firmware_k8200_v2.1.1.zip)
* see also https://github.com/CONSULitAS/Marlin-K8200/tree/Vellemann_firmware_k8200_v2.1.1.zip
* [firmware_k8200_marlinv2.zip](http://www.k8200.eu/downloads/files/downloads/firmware_k8200_marlinv2.zip)
* V2 (with LCD/SD-Support, date branched: 2013-06-05): [firmware_k8200_marlinv2.zip](http://www.k8200.eu/downloads/files/downloads/firmware_k8200_marlinv2.zip)
* see also https://github.com/CONSULitAS/Marlin-K8200/tree/Vellemann_firmware_k8200_marlinv2.zip
* [firmware_k8200_marlinv1.zip](http://www.k8200.eu/downloads/files/downloads/firmware_k8200_marlinv1.zip)
* V1 (without LCD/SD-Support, date branched: 2012-10-02): [firmware_k8200_marlinv1.zip](http://www.k8200.eu/downloads/files/downloads/firmware_k8200_marlinv1.zip)
* see also https://github.com/CONSULitAS/Marlin-K8200/tree/Vellemann_firmware_k8200_marlinv1.zip

76
Marlin/example_configurations/SCARA/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -57,7 +57,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -289,44 +288,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -369,6 +361,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -402,17 +395,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS 225
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -433,7 +429,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -625,7 +621,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -645,9 +641,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/SCARA/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

76
Marlin/example_configurations/WITBOX/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(bq Witbox)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -257,44 +256,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -337,6 +329,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z true
@ -370,17 +363,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define Z_MAX_POS 200
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -401,7 +397,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -593,7 +589,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -613,9 +609,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/WITBOX/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

816
Marlin/example_configurations/delta/biv2.5/Configuration.h

@ -0,0 +1,816 @@
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
//===========================================================================
//============================= Getting Started =============================
//===========================================================================
/*
Here are some standard links for getting your machine calibrated:
* http://reprap.org/wiki/Calibration
* http://youtu.be/wAL9d7FgInk
* http://calculator.josefprusa.cz
* http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide
* http://www.thingiverse.com/thing:5573
* https://sites.google.com/site/repraplogphase/calibration-of-your-reprap
* http://www.thingiverse.com/thing:298812
*/
// This configuration file contains the basic settings.
// Advanced settings can be found in Configuration_adv.h
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
//===========================================================================
//============================= DELTA Printer ===============================
//===========================================================================
// For a Delta printer replace the configuration files with the files in the
// example_configurations/delta directory.
//
//===========================================================================
//============================= SCARA Printer ===============================
//===========================================================================
// For a Delta printer replace the configuration files with the files in the
// example_configurations/SCARA directory.
//
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
//#define STRING_SPLASH_LINE2 STRING_VERSION_CONFIG_H // will be shown during bootup in line2
// SERIAL_PORT selects which serial port should be used for communication with the host.
// This allows the connection of wireless adapters (for instance) to non-default port pins.
// Serial port 0 is still used by the Arduino bootloader regardless of this setting.
#define SERIAL_PORT 0
// This determines the communication speed of the printer
#define BAUDRATE 250000
// This enables the serial port associated to the Bluetooth interface
//#define BTENABLED // Enable BT interface on AT90USB devices
// The following define selects which electronics board you have.
// Please choose the name from boards.h that matches your setup
#ifndef MOTHERBOARD
#define MOTHERBOARD BOARD_RUMBA
#endif
// Optional custom name for your RepStrap or other custom machine
// Displayed in the LCD "Ready" message
#define CUSTOM_MACHINE_NAME "BI V2.5"
// 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"
// This defines the number of extruders
#define EXTRUDERS 2
//// The following define selects which power supply you have. Please choose the one that matches your setup
// 1 = ATX
// 2 = X-Box 360 203Watts (the blue wire connected to PS_ON and the red wire to VCC)
#define POWER_SUPPLY 1
// Define this to have the electronics keep the power supply off on startup. If you don't know what this is leave it.
// #define PS_DEFAULT_OFF
//===========================================================================
//============================== Delta Settings =============================
//===========================================================================
// Enable DELTA kinematics and most of the default configuration for Deltas
#define DELTA
// Make delta curves from many straight lines (linear interpolation).
// This is a trade-off between visible corners (not enough segments)
// and processor overload (too many expensive sqrt calls).
#define DELTA_SEGMENTS_PER_SECOND 100
// NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them
// Center-to-center distance of the holes in the diagonal push rods.
#define DELTA_DIAGONAL_ROD 440.0 // mm
// Horizontal offset from middle of printer to smooth rod center.
#define DELTA_SMOOTH_ROD_OFFSET 330.0 // mm
// Horizontal offset of the universal joints on the end effector.
#define DELTA_EFFECTOR_OFFSET 50.0 // mm
// Horizontal offset of the universal joints on the carriages.
#define DELTA_CARRIAGE_OFFSET 20.0 // mm
// Horizontal distance bridged by diagonal push rods when effector is centered.
#define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET-DELTA_EFFECTOR_OFFSET-DELTA_CARRIAGE_OFFSET)
// Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers).
#define DELTA_PRINTABLE_RADIUS 160
//===========================================================================
//============================= Thermal Settings ============================
//===========================================================================
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
// 998 and 999 are Dummy Tables. They will ALWAYS read 25°C or the temperature defined below.
// Use it for Testing or Development purposes. NEVER for production machine.
// #define DUMMY_THERMISTOR_998_VALUE 25
// #define DUMMY_THERMISTOR_999_VALUE 100
// :{ '0': "Not used", '4': "10k !! do not use for a hotend. Bad resolution at high temp. !!", '1': "100k / 4.7k - EPCOS", '51': "100k / 1k - EPCOS", '6': "100k / 4.7k EPCOS - Not as accurate as Table 1", '5': "100K / 4.7k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '7': "100k / 4.7k Honeywell 135-104LAG-J01", '71': "100k / 4.7k Honeywell 135-104LAF-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'", '60': "100k Maker's Tool Works Kapton Bed Thermistor beta=3950", '55': "100k / 1k - ATC Semitec 104GT-2 (Used in ParCan & J-Head)", '2': "200k / 4.7k - ATC Semitec 204GT-2", '52': "200k / 1k - ATC Semitec 204GT-2", '-2': "Thermocouple + MAX6675 (only for sensor 0)", '-1': "Thermocouple + AD595", '3': "Mendel-parts / 4.7k", '1047': "Pt1000 / 4.7k", '1010': "Pt1000 / 1k (non standard)", '20': "PT100 (Ultimainboard V2.x)", '147': "Pt100 / 4.7k", '110': "Pt100 / 1k (non-standard)", '998': "Dummy 1", '999': "Dummy 2" }
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 5
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 1
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
// Actual temperature must be close to target for this long before M109 returns success
#define TEMP_RESIDENCY_TIME 10 // (seconds)
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
// to check that the wiring to the thermistor is not broken.
// Otherwise this would lead to the heater being powered on all the time.
#define HEATER_0_MINTEMP 5
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define HEATER_3_MINTEMP 5
#define BED_MINTEMP 5
// When temperature exceeds max temp, your heater will be switched off.
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
// You should use MINTEMP for thermistor short/failure protection.
#define HEATER_0_MAXTEMP 275
#define HEATER_1_MAXTEMP 275
#define HEATER_2_MAXTEMP 275
#define HEATER_3_MAXTEMP 275
#define BED_MAXTEMP 150
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
// If you want the M105 heater power reported in watts, define the BED_WATTS, and (shared for all extruders) EXTRUDER_WATTS
//#define EXTRUDER_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
//===========================================================================
//============================= PID Settings ================================
//===========================================================================
// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning
// Comment the following line to disable PID and enable bang-bang.
#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
#ifdef PIDTEMP
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
//#define PID_PARAMS_PER_EXTRUDER // Uses separate PID parameters for each extruder (useful for mismatched extruders)
// Set/get with gcode: M301 E[extruder number, 0-2]
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_INTEGRAL_DRIVE_MAX PID_MAX //limit for the integral term
#define K1 0.95 //smoothing factor within the PID
// 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
// MakerGear
// #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
#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.
//#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)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
//#define PID_BED_DEBUG // Sends debug data to the serial port.
#ifdef PIDTEMPBED
//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
//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
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
//this prevents dangerous Extruder moves, i.e. if the temperature is under the limit
//can be software-disabled for whatever purposes by
#define PREVENT_DANGEROUS_EXTRUDE
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// Parameters for all extruder heaters
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 120 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 4 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
//===========================================================================
// Uncomment this option to enable CoreXY kinematics
// #define COREXY
// Enable this option for Toshiba steppers
// #define CONFIG_STEPPERS_TOSHIBA
// coarse Endstop Settings
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
#ifndef ENDSTOPPULLUPS
// fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined
// #define ENDSTOPPULLUP_XMAX
// #define ENDSTOPPULLUP_YMAX
// #define ENDSTOPPULLUP_ZMAX
// #define ENDSTOPPULLUP_XMIN
// #define ENDSTOPPULLUP_YMIN
// #define ENDSTOPPULLUP_ZMIN
#endif
// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup).
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool X_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MAX_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic of the endstop.
//#define DISABLE_MAX_ENDSTOPS
#define DISABLE_MIN_ENDSTOPS // Deltas only use min endstops for probing
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
#define X_ENABLE_ON 0
#define Y_ENABLE_ON 0
#define Z_ENABLE_ON 0
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
#define DISABLE_E false // For all extruders
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way.
#define INVERT_X_DIR false // DELTA does not invert
#define INVERT_Y_DIR false
#define INVERT_Z_DIR false
#define INVERT_E0_DIR false
#define INVERT_E1_DIR false
#define INVERT_E2_DIR false
#define INVERT_E3_DIR false
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
#define X_HOME_DIR 1 // deltas always home to max
#define Y_HOME_DIR 1
#define Z_HOME_DIR 1
#define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
// Travel limits after homing (units are in mm)
#define X_MIN_POS -DELTA_PRINTABLE_RADIUS
#define Y_MIN_POS -DELTA_PRINTABLE_RADIUS
#define Z_MIN_POS 0
#define X_MAX_POS DELTA_PRINTABLE_RADIUS
#define Y_MAX_POS DELTA_PRINTABLE_RADIUS
#define Z_MAX_POS MANUAL_Z_HOME_POS
//===========================================================================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
//===========================================================================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
// #define MESH_BED_LEVELING // Enable mesh bed leveling
#ifdef MANUAL_BED_LEVELING
#define MBL_Z_STEP 0.025
#endif // MANUAL_BED_LEVELING
#ifdef MESH_BED_LEVELING
#define MESH_MIN_X 10
#define MESH_MAX_X (X_MAX_POS - MESH_MIN_X)
#define MESH_MIN_Y 10
#define MESH_MAX_Y (Y_MAX_POS - MESH_MIN_Y)
#define MESH_NUM_X_POINTS 3 // Don't use more than 7 points per axis, implementation limited
#define MESH_NUM_Y_POINTS 3
#define MESH_HOME_SEARCH_Z 4 // Z after Home, bed somewhere below but above 0.0
#endif // MESH_BED_LEVELING
//===========================================================================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
//#define Z_PROBE_REPEATABILITY_TEST // Z-Probe Repeatability test is not supported in Deltas yet.
#ifdef ENABLE_AUTO_BED_LEVELING
// There are 2 different ways to specify probing locations
//
// - "grid" mode
// Probe several points in a rectangular grid.
// You specify the rectangle and the density of sample points.
// This mode is preferred because there are more measurements.
//
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You specify the XY coordinates of all 3 points.
// Enable this to sample the bed in a grid (least squares solution)
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID // Deltas only support grid mode
#ifdef AUTO_BED_LEVELING_GRID
#define DELTA_PROBABLE_RADIUS (DELTA_PRINTABLE_RADIUS - 10)
#define LEFT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
#define RIGHT_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
#define FRONT_PROBE_BED_POSITION -DELTA_PROBABLE_RADIUS
#define BACK_PROBE_BED_POSITION DELTA_PROBABLE_RADIUS
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
// Non-linear bed leveling will be used.
// Compensate by interpolating between the nearest four Z probe values for each point.
// Useful for deltas where the print surface may appear like a bowl or dome shape.
// Works best with ACCURATE_BED_LEVELING_POINTS 5 or higher.
#define AUTO_BED_LEVELING_GRID_POINTS 9
#else // !AUTO_BED_LEVELING_GRID
// 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
#endif // AUTO_BED_LEVELING_GRID
// Offsets to the probe relative to the extruder tip (Hotend - Probe)
// X and Y offsets must be integers
#define X_PROBE_OFFSET_FROM_EXTRUDER 0 // Probe on: -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER -10 // Probe on: -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -3.5 // -below (always!)
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
// Be sure you have this distance over your Z_MAX_POS in case
#define XY_TRAVEL_SPEED 4000 // X and Y axis travel speed between probes, in mm/min
#define Z_RAISE_BEFORE_PROBING 15 //How much the extruder will be raised before traveling to the first probing point.
#define Z_RAISE_BETWEEN_PROBINGS 5 //How much the extruder will be raised when traveling from between next probing points
#define Z_RAISE_AFTER_PROBING 50 //How much the extruder will be raised after the last probing point.
// #define Z_PROBE_END_SCRIPT "G1 Z10 F12000\nG1 X15 Y330\nG1 Z0.5\nG1 Z10" //These commands will be executed in the end of G29 routine.
//Useful to retract a deployable probe.
//#define Z_PROBE_SLED // turn on if you have a z-probe mounted on a sled like those designed by Charles Bell
//#define SLED_DOCKING_OFFSET 5 // the extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like.
// Allen key retractable z-probe as seen on many Kossel delta printers - http://reprap.org/wiki/Kossel#Automatic_bed_leveling_probe
// Deploys by touching z-axis belt. Retracts by pushing the probe down. Uses Z_MIN_PIN.
//#define Z_PROBE_ALLEN_KEY
#ifdef Z_PROBE_ALLEN_KEY
#define Z_PROBE_ALLEN_KEY_DEPLOY_X 30
#define Z_PROBE_ALLEN_KEY_DEPLOY_Y DELTA_PRINTABLE_RADIUS
#define Z_PROBE_ALLEN_KEY_DEPLOY_Z 100
#define Z_PROBE_ALLEN_KEY_STOW_X -64
#define Z_PROBE_ALLEN_KEY_STOW_Y 56
#define Z_PROBE_ALLEN_KEY_STOW_Z 23
#define Z_PROBE_ALLEN_KEY_STOW_DEPTH 20
#endif
//If defined, the Probe servo will be turned on only during movement and then turned off to avoid jerk
//The value is the delay to turn the servo off after powered on - depends on the servo speed; 300ms is good value, but you can try lower it.
// You MUST HAVE the SERVO_ENDSTOPS defined to use here a value higher than zero otherwise your code will not compile.
// #define PROBE_SERVO_DEACTIVATION_DELAY 300
//If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
//it is highly recommended you let this Z_SAFE_HOMING enabled!!!
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area.
// When defined, it will:
// - Allow Z homing only after X and Y homing AND stepper drivers still enabled
// - If stepper drivers timeout, it will need X and Y homing again before Z homing
// - Position the probe in a defined XY point before Z Homing when homing all axis (G28)
// - Block Z homing only when the probe is outside bed area.
#ifdef Z_SAFE_HOMING
#define Z_SAFE_HOMING_X_POINT (X_MAX_LENGTH/2) // X point for Z homing when homing all axis (G28)
#define Z_SAFE_HOMING_Y_POINT (Y_MAX_LENGTH/2) // Y point for Z homing when homing all axis (G28)
#endif
// Support for a dedicated Z PROBE endstop separate from the Z MIN endstop.
// If you would like to use both a Z PROBE and a Z MIN endstop together or just a Z PROBE with a custom pin, uncomment #define Z_PROBE_ENDSTOP and read the instructions below.
// If you want to still use the Z min endstop for homing, disable Z_SAFE_HOMING above. Eg; to park the head outside the bed area when homing with G28.
// WARNING: The Z MIN endstop will need to set properly as it would without a Z PROBE to prevent head crashes and premature stopping during a print.
// To use a separate Z PROBE endstop, you must have a Z_PROBE_PIN defined in the pins.h file for your control board.
// If you are using a servo based Z PROBE, you will need to enable NUM_SERVOS, SERVO_ENDSTOPS and SERVO_ENDSTOPS_ANGLES in the R/C Servo below.
// RAMPS 1.3/1.4 boards may be able to use the 5V, Ground and the D32 pin in the Aux 4 section of the RAMPS board. Use 5V for powered sensors, otherwise connect to ground and D32
// for normally closed configuration and 5V and D32 for normally open configurations. Normally closed configuration is advised and assumed.
// The D32 pin in Aux 4 on RAMPS maps to the Arduino D32 pin. Z_PROBE_PIN is setting the pin to use on the Arduino. Since the D32 pin on the RAMPS maps to D32 on Arduino, this works.
// D32 is currently selected in the RAMPS 1.3/1.4 pin file. All other boards will need changes to the respective pins_XXXXX.h file.
// WARNING: Setting the wrong pin may have unexpected and potentially disastrous outcomes. Use with caution and do your homework.
//#define Z_PROBE_ENDSTOP
#endif // ENABLE_AUTO_BED_LEVELING
// The position of the homing switches
#define MANUAL_HOME_POSITIONS // If defined, MANUAL_*_HOME_POS below will be used
//#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
// Manual homing switch locations:
// For deltabots this means top and center of the Cartesian print volume.
#ifdef MANUAL_HOME_POSITIONS
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 405 // For delta: Distance between nozzle and print surface after homing.
#endif
/**
* MOVEMENT SETTINGS
*/
// delta homing speeds must be the same on xyz
#define HOMING_FEEDRATE {200*30, 200*30, 200*30, 0} // set the homing speeds (mm/min)
// default settings
// delta speeds must be the same on xyz
#define DEFAULT_AXIS_STEPS_PER_UNIT {72.9, 72.9, 72.9, 291} // default steps per unit for BI v2.5 (cable drive)
#define DEFAULT_MAX_FEEDRATE {500, 500, 500, 150} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,9000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // E acceleration in mm/s^2 for retracts
#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration in mm/s^2 for travel (non printing) moves
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
// For the other hotends it is their distance from the extruder 0 hotend.
// #define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
// #define EXTRUDER_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XYJERK 15.0 // (mm/sec)
#define DEFAULT_ZJERK 15.0 // (mm/sec) Must be same as XY for delta
#define DEFAULT_EJERK 5.0 // (mm/sec)
//=============================================================================
//============================= Additional Features ===========================
//=============================================================================
// Custom M code points
#define CUSTOM_M_CODES
#ifdef CUSTOM_M_CODES
#ifdef ENABLE_AUTO_BED_LEVELING
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
#define Z_PROBE_OFFSET_RANGE_MIN -20
#define Z_PROBE_OFFSET_RANGE_MAX 20
#endif
#endif
// EEPROM
// The microcontroller can store settings in the EEPROM, e.g. max velocity...
// M500 - stores parameters in EEPROM
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
//define this to enable EEPROM support
//#define EEPROM_SETTINGS
#ifdef EEPROM_SETTINGS
// To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
#define EEPROM_CHITCHAT // please keep turned on if you can.
#endif
// Preheat Constants
#define PLA_PREHEAT_HOTEND_TEMP 180
#define PLA_PREHEAT_HPB_TEMP 70
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
#define ABS_PREHEAT_HOTEND_TEMP 240
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
// Choose ONE of these 3 charsets. This has to match your hardware. Ignored for full graphic display.
// To find out what type you have - compile with (test) - upload - click to get the menu. You'll see two typical lines from the upper half of the charset.
// See also documentation/LCDLanguageFont.md
#define DISPLAY_CHARSET_HD44780_JAPAN // this is the most common hardware
//#define DISPLAY_CHARSET_HD44780_WESTERN
//#define DISPLAY_CHARSET_HD44780_CYRILLIC
//#define ULTRA_LCD //general LCD support, also 16x2
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
//#define SDSUPPORT // Enable SD Card Support in Hardware Console
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
//#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne
//#define PANEL_ONE
// The MaKr3d Makr-Panel with graphic controller and SD support
// http://reprap.org/wiki/MaKr3d_MaKrPanel
//#define MAKRPANEL
// The Panucatt Devices Viki 2.0 and mini Viki with Graphic LCD
// http://panucatt.com
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
//#define VIKI2
//#define miniVIKI
// The RepRapDiscount Smart Controller (white PCB)
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
// The GADGETS3D G3D LCD/SD Controller (blue PCB)
// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel
//#define G3D_PANEL
// The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB)
// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller
//
// ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib
#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER
// The RepRapWorld REPRAPWORLD_KEYPAD v1.1
// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626
//#define REPRAPWORLD_KEYPAD
//#define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 // how much should be moved when a key is pressed, eg 10.0 means 10mm per click
// The Elefu RA Board Control Panel
// http://www.elefu.com/index.php?route=product/product&product_id=53
// REMEMBER TO INSTALL LiquidCrystal_I2C.h in your ARDUINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
//#define RA_CONTROL_PANEL
// Delta calibration menu
// uncomment to add three points calibration menu option.
// See http://minow.blogspot.com/index.html#4918805519571907051
// If needed, adjust the X, Y, Z calibration coordinates
// in ultralcd.cpp@lcd_delta_calibrate_menu()
// #define DELTA_CALIBRATION_MENU
/**
* I2C Panels
*/
//#define LCD_I2C_SAINSMART_YWROBOT
// PANELOLU2 LCD with status LEDs, separate encoder and click inputs
//#define LCD_I2C_PANELOLU2
// Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs
//#define LCD_I2C_VIKI
// Shift register panels
// ---------------------
// 2 wire Non-latching LCD SR from:
// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/schematics#!shiftregister-connection
//#define SAV_3DLCD
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
//#define FAST_PWM_FAN
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
// which is not as annoying as with the hardware PWM. On the other hand, if this frequency
// is too low, you should also increment SOFT_PWM_SCALE.
//#define FAN_SOFT_PWM
// Incrementing this by 1 will double the software PWM frequency,
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
// However, control resolution will be halved for each increment;
// at zero value, there are 128 effective control positions.
#define SOFT_PWM_SCALE 0
// Temperature status LEDs that display the hotend and bet temperature.
// If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
// Otherwise the RED led is on. There is 1C hysteresis.
//#define TEMP_STAT_LEDS
// M240 Triggers a camera by emulating a Canon RC-1 Remote
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
// #define PHOTOGRAPH_PIN 23
// SF send wrong arc g-codes when using Arc Point as fillet procedure
//#define SF_ARC_FIX
// Support for the BariCUDA Paste Extruder.
//#define BARICUDA
//define BlinkM/CyzRgb Support
//#define BLINKM
/*********************************************************************\
* R/C SERVO support
* Sponsored by TrinityLabs, Reworked by codexmas
**********************************************************************/
// Number of servos
//
// If you select a configuration below, this will receive a default value and does not need to be set manually
// set it manually if you have more servos than extruders and wish to manually control some
// leaving it undefined or defining as 0 will disable the servo subsystem
// If unsure, leave commented / disabled
//
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
// Servo Endstops
//
// This allows for servo actuated endstops, primary usage is for the Z Axis to eliminate calibration or bed height changes.
// Use M851 to set the z-probe vertical offset from the nozzle. Store that setting with M500.
//
//#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
//#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 70,0} // X,Y,Z Axis Extend and Retract angles
/**********************************************************************\
* Support for a filament diameter sensor
* Also allows adjustment of diameter at print time (vs at slicing)
* Single extruder only at this point (extruder 0)
*
* Motherboards
* 34 - RAMPS1.4 - uses Analog input 5 on the AUX2 connector
* 81 - Printrboard - Uses Analog input 2 on the Exp1 connector (version B,C,D,E)
* 301 - Rambo - uses Analog input 3
* Note may require analog pins to be defined for different motherboards
**********************************************************************/
// Uncomment below to enable
//#define FILAMENT_SENSOR
#define FILAMENT_SENSOR_EXTRUDER_NUM 0 //The number of the extruder that has the filament sensor (0,1,2)
#define MEASUREMENT_DELAY_CM 14 //measurement delay in cm. This is the distance from filament sensor to middle of barrel
#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 //Enter the diameter (in mm) of the filament generally used (3.0 mm or 1.75 mm) - this is then used in the slicer software. Used for sensor reading validation
#define MEASURED_UPPER_LIMIT 3.30 //upper limit factor used for sensor reading validation in mm
#define MEASURED_LOWER_LIMIT 1.90 //lower limit factor for sensor reading validation in mm
#define MAX_MEASUREMENT_DELAY 20 //delay buffer size in bytes (1 byte = 1cm)- limits maximum measurement delay allowable (must be larger than MEASUREMENT_DELAY_CM and lower number saves RAM)
//defines used in the code
#define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA //set measured to nominal initially
//When using an LCD, uncomment the line below to display the Filament sensor data on the last line instead of status. Status will appear for 5 sec.
//#define FILAMENT_LCD_DISPLAY
#include "Configuration_adv.h"
#include "thermistortables.h"
#endif //CONFIGURATION_H

552
Marlin/example_configurations/delta/biv2.5/Configuration_adv.h

@ -0,0 +1,552 @@
#ifndef CONFIGURATION_ADV_H
#define CONFIGURATION_ADV_H
#include "Conditionals.h"
// @section temperature
//===========================================================================
//=============================Thermal Settings ============================
//===========================================================================
#ifdef BED_LIMIT_SWITCHING
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS
#endif
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
//// Heating sanity check:
// This waits for the watch period in milliseconds whenever an M104 or M109 increases the target temperature
// If the temperature has not increased at the end of that period, the target temperature is set to zero.
// It can be reset with another M104/M109. This check is also only triggered if the target temperature and the current temperature
// differ by at least 2x WATCH_TEMP_INCREASE
#define WATCH_TEMP_PERIOD 40000 //40 seconds
#define WATCH_TEMP_INCREASE 10 //Heat up at least 10 degree in 20 seconds
#ifdef PIDTEMP
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
#define PID_ADD_EXTRUSION_RATE
#ifdef PID_ADD_EXTRUSION_RATE
#define DEFAULT_Kc (1) //heating power=Kc*(e_speed)
#endif
#endif
//automatic temperature: The hot end target temperature is calculated by all the buffered lines of gcode.
//The maximum buffered steps/sec of the extruder motor are called "se".
//You enter the autotemp mode by a M109 S<mintemp> B<maxtemp> F<factor>
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
// you exit the value by any M109 without F*
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
// on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
#define AUTOTEMP
#ifdef AUTOTEMP
#define AUTOTEMP_OLDWEIGHT 0.98
#endif
//Show Temperature ADC value
//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
//#define SHOW_TEMP_ADC_VALUES
// @section extruder
// extruder run-out prevention.
//if the machine is idle, and the temperature over MINTEMP, every couple of SECONDS some filament is extruded
//#define EXTRUDER_RUNOUT_PREVENT
#define EXTRUDER_RUNOUT_MINTEMP 190
#define EXTRUDER_RUNOUT_SECONDS 30.
#define EXTRUDER_RUNOUT_ESTEPS 14. //mm filament
#define EXTRUDER_RUNOUT_SPEED 1500. //extrusion speed
#define EXTRUDER_RUNOUT_EXTRUDE 100
// @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
//This is for controlling a fan to cool down the stepper drivers
//it will turn on when any driver is enabled
//and turn off after the set amount of seconds from last driver being disabled again
#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable)
#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run
#define CONTROLLERFAN_SPEED 255 // == full speed
// 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
// @section extruder
// Extruder cooling fans
// Configure fan pin outputs to automatically turn on/off when the associated
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
//===========================================================================
//=============================Mechanical Settings===========================
//===========================================================================
// @section homing
#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
// @section extras
//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats.
// A single Z stepper driver is usually used to drive 2 stepper motors.
// Uncomment this define to utilize a separate stepper driver for each Z axis motor.
// Only a few motherboards support this, like RAMPS, which have dual extruder support (the 2nd, often unused, extruder driver is used
// to control the 2nd Z axis stepper motor). The pins are currently only defined for a RAMPS motherboards.
// On a RAMPS (or other 5 driver) motherboard, using this feature will limit you to using 1 extruder.
//#define Z_DUAL_STEPPER_DRIVERS
#ifdef Z_DUAL_STEPPER_DRIVERS
// Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper.
// That way the machine is capable to align the bed during home, since both Z steppers are homed.
// There is also an implementation of M666 (software endstops adjustment) to this feature.
// After Z homing, this adjustment is applied to just one of the steppers in order to align the bed.
// One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2.
// If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive.
// Play a little bit with small adjustments (0.5mm) and check the behaviour.
// The M119 (endstops report) will start reporting the Z2 Endstop as well.
#define Z_DUAL_ENDSTOPS
#ifdef Z_DUAL_ENDSTOPS
#define Z2_STEP_PIN E2_STEP_PIN // Stepper to be used to Z2 axis.
#define Z2_DIR_PIN E2_DIR_PIN
#define Z2_ENABLE_PIN E2_ENABLE_PIN
#define Z2_MAX_PIN 36 //Endstop used for Z2 axis. In this case I'm using XMAX in a Rumba Board (pin 36)
const bool Z2_MAX_ENDSTOP_INVERTING = false;
#define DISABLE_XMAX_ENDSTOP //Better to disable the XMAX to avoid conflict. Just rename "XMAX_ENDSTOP" by the endstop you are using for Z2 axis.
#endif
#endif // Z_DUAL_STEPPER_DRIVERS
// Same again but for Y Axis.
//#define Y_DUAL_STEPPER_DRIVERS
// Define if the two Y drives need to rotate in opposite directions
#define INVERT_Y2_VS_Y_DIR true
// 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.
//#define DUAL_X_CARRIAGE
#ifdef 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 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
#define X2_HOME_POS X2_MAX_POS // default home position is the maximum carriage position
// However: In this mode the EXTRUDER_OFFSET_X value for the second extruder provides a software
// override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops
// without modifying the firmware (through the "M218 T1 X???" command).
// Remember: you should set the second extruder x-offset to 0 in your slicer.
// Pins for second x-carriage stepper driver (defined here to avoid further complicating pins.h)
#define X2_ENABLE_PIN 29
#define X2_STEP_PIN 25
#define X2_DIR_PIN 23
// There are a few selectable movement modes for dual x-carriages using M605 S<mode>
// Mode 0: Full control. The slicer has full control over both x-carriages and can achieve optimal travel results
// as long as it supports dual x-carriages. (M605 S0)
// Mode 1: Auto-park mode. The firmware will automatically park and unpark the x-carriages on tool changes so
// that additional slicer support is not required. (M605 S1)
// Mode 2: Duplication mode. The firmware will transparently make the second x-carriage and extruder copy all
// actions of the first x-carriage. This allows the printer to print 2 arbitrary items at
// once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm])
// This is the default power-up mode which can be later using M605.
#define DEFAULT_DUAL_X_CARRIAGE_MODE 0
// Default settings in "Auto-park Mode"
#define TOOLCHANGE_PARK_ZLIFT 0.2 // the distance to raise Z axis when parking an extruder
#define TOOLCHANGE_UNPARK_ZLIFT 1 // the distance to raise Z axis when unparking an extruder
// Default x offset in duplication mode (typically set to half print bed width)
#define DEFAULT_DUPLICATION_X_OFFSET 100
#endif //DUAL_X_CARRIAGE
// @section homing
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
#define X_HOME_BUMP_MM 5
#define Y_HOME_BUMP_MM 5
#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
// @section machine
//By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step.
#define INVERT_X_STEP_PIN false
#define INVERT_Y_STEP_PIN false
#define INVERT_Z_STEP_PIN false
#define INVERT_E_STEP_PIN false
// Default stepper release if idle. Set to 0 to deactivate.
#define DEFAULT_STEPPER_DEACTIVE_TIME 0
#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate
#define DEFAULT_MINTRAVELFEEDRATE 0.0
// @section lcd
#ifdef ULTIPANEL
#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
// @section extras
// minimum time in microseconds that a movement needs to take if the buffer is emptied.
#define DEFAULT_MINSEGMENTTIME 20000
// If defined the movements slow down when the look ahead buffer is only half full
// (don't use SLOWDOWN with DELTA because DELTA generates hundreds of segments per second)
//#define SLOWDOWN
// Frequency limit
// See nophead's blog for more info
// Not working O
//#define XY_FREQUENCY_LIMIT 15
// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end
// of the buffer and all stops. This should not be much greater than zero and should only be changed
// if unwanted behavior is observed on a user's machine when running at very slow speeds.
#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec)
// 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]
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
//#define DIGIPOT_I2C
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
#define DIGIPOT_I2C_NUM_CHANNELS 8
// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}
//===========================================================================
//=============================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 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
// @section lcd
#ifdef SDSUPPORT
// If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
// You can get round this by connecting a push button or single throw switch to the pin defined as SDCARDCARDDETECT
// in the pins.h file. When using a push button pulling the pin to ground this will need inverted. This setting should
// be commented out otherwise
#define SDCARDDETECTINVERTED
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
// if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
// using:
//#define MENU_ADDAUTOSTART
// Show a progress bar on HD44780 LCDs for SD printing
//#define LCD_PROGRESS_BAR
#ifdef 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
#endif
#endif // SDSUPPORT
// @section more
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
//#define USE_WATCHDOG
#ifdef USE_WATCHDOG
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
// However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
//#define WATCHDOG_RESET_MANUAL
#endif
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
// @section lcd
// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
// it can e.g. be used to change z-positions in the print startup phase in real-time
// does not respect endstops!
//#define BABYSTEPPING
#ifdef BABYSTEPPING
#define BABYSTEP_XY //not only z, but also XY in the menu. more clutter, more functions
#define BABYSTEP_INVERT_Z false //true for inverse movements in Z
#define BABYSTEP_Z_MULTIPLICATOR 2 //faster z movements
#endif
// @section extruder
// extruder advance constant (s2/mm3)
//
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2
//
// Hooke's law says: force = k * distance
// Bernoulli's principle says: v ^ 2 / 2 + g . h + pressure / density = constant
// so: v ^ 2 is proportional to number of steps we advance the extruder
//#define ADVANCE
#ifdef ADVANCE
#define EXTRUDER_ADVANCE_K .0
#define D_FILAMENT 2.85
#define STEPS_MM_E 836
#endif
// @section extras
// Arc interpretation settings:
#define MM_PER_ARC_SEGMENT 1
#define N_ARC_CORRECTION 25
const unsigned int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
// @section temperature
// Control heater 0 and heater 1 in parallel.
//#define HEATERS_PARALLEL
//===========================================================================
//================================= Buffers =================================
//===========================================================================
// @section hidden
// 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, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#ifdef SDSUPPORT
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else
#define BLOCK_BUFFER_SIZE 16 // maximize block buffer
#endif
// @section more
//The ASCII buffer for receiving from the serial:
#define MAX_CMD_SIZE 96
#define BUFSIZE 4
// @section fwretract
// Firmware based and LCD controlled retract
// M207 and M208 can be used to define parameters for the retraction.
// The retraction can be called by the slicer using G10 and G11
// until then, intended retractions can be detected by moves that only extrude and the direction.
// the moves are than replaced by the firmware controlled ones.
#define FWRETRACT //ONLY PARTIALLY TESTED
#ifdef FWRETRACT
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
#define RETRACT_LENGTH 5 //default retract length (positive mm)
#define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change
#define RETRACT_FEEDRATE 100 //default feedrate for retracting (mm/s)
#define RETRACT_ZLIFT 0 //default retract Z-lift
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change)
#define RETRACT_RECOVER_FEEDRATE 100 //default feedrate for recovering from retraction (mm/s)
#endif
// Add support for experimental filament exchange support M600; requires display
#ifdef ULTIPANEL
//#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 3
#define FILAMENTCHANGE_YPOS 3
#define FILAMENTCHANGE_ZADD 10
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -100
#endif
#endif
/******************************************************************************\
* enable this section if you have TMC26X motor drivers.
* you need to import the TMC26XStepper library into the arduino IDE for this
******************************************************************************/
// @section tmc
//#define HAVE_TMCDRIVER
#ifdef HAVE_TMCDRIVER
// #define X_IS_TMC
#define X_MAX_CURRENT 1000 //in mA
#define X_SENSE_RESISTOR 91 //in mOhms
#define X_MICROSTEPS 16 //number of microsteps
// #define X2_IS_TMC
#define X2_MAX_CURRENT 1000 //in mA
#define X2_SENSE_RESISTOR 91 //in mOhms
#define X2_MICROSTEPS 16 //number of microsteps
// #define Y_IS_TMC
#define Y_MAX_CURRENT 1000 //in mA
#define Y_SENSE_RESISTOR 91 //in mOhms
#define Y_MICROSTEPS 16 //number of microsteps
// #define Y2_IS_TMC
#define Y2_MAX_CURRENT 1000 //in mA
#define Y2_SENSE_RESISTOR 91 //in mOhms
#define Y2_MICROSTEPS 16 //number of microsteps
// #define Z_IS_TMC
#define Z_MAX_CURRENT 1000 //in mA
#define Z_SENSE_RESISTOR 91 //in mOhms
#define Z_MICROSTEPS 16 //number of microsteps
// #define Z2_IS_TMC
#define Z2_MAX_CURRENT 1000 //in mA
#define Z2_SENSE_RESISTOR 91 //in mOhms
#define Z2_MICROSTEPS 16 //number of microsteps
// #define E0_IS_TMC
#define E0_MAX_CURRENT 1000 //in mA
#define E0_SENSE_RESISTOR 91 //in mOhms
#define E0_MICROSTEPS 16 //number of microsteps
// #define E1_IS_TMC
#define E1_MAX_CURRENT 1000 //in mA
#define E1_SENSE_RESISTOR 91 //in mOhms
#define E1_MICROSTEPS 16 //number of microsteps
// #define E2_IS_TMC
#define E2_MAX_CURRENT 1000 //in mA
#define E2_SENSE_RESISTOR 91 //in mOhms
#define E2_MICROSTEPS 16 //number of microsteps
// #define E3_IS_TMC
#define E3_MAX_CURRENT 1000 //in mA
#define E3_SENSE_RESISTOR 91 //in mOhms
#define E3_MICROSTEPS 16 //number of microsteps
#endif
/******************************************************************************\
* enable this section if you have L6470 motor drivers.
* you need to import the L6470 library into the arduino IDE for this
******************************************************************************/
// @section l6470
//#define HAVE_L6470DRIVER
#ifdef HAVE_L6470DRIVER
// #define X_IS_L6470
#define X_MICROSTEPS 16 //number of microsteps
#define X_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull 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_IS_L6470
#define X2_MICROSTEPS 16 //number of microsteps
#define X2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define X2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define X2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Y_IS_L6470
#define Y_MICROSTEPS 16 //number of microsteps
#define Y_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Y_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Y2_IS_L6470
#define Y2_MICROSTEPS 16 //number of microsteps
#define Y2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Y2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Y2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Z_IS_L6470
#define Z_MICROSTEPS 16 //number of microsteps
#define Z_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Z_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define Z2_IS_L6470
#define Z2_MICROSTEPS 16 //number of microsteps
#define Z2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define Z2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define Z2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E0_IS_L6470
#define E0_MICROSTEPS 16 //number of microsteps
#define E0_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E0_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E0_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E1_IS_L6470
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_MICROSTEPS 16 //number of microsteps
#define E1_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E1_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E1_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E2_IS_L6470
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_MICROSTEPS 16 //number of microsteps
#define E2_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E2_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E2_STALLCURRENT 1500 //current in mA where the driver will detect a stall
// #define E3_IS_L6470
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_MICROSTEPS 16 //number of microsteps
#define E3_K_VAL 50 // 0 - 255, Higher values, are higher power. Be carefull not to go too high
#define E3_OVERCURRENT 2000 //maxc current in mA. If the current goes over this value, the driver will switch off
#define E3_STALLCURRENT 1500 //current in mA where the driver will detect a stall
#endif
#include "Conditionals.h"
#include "SanityCheck.h"
#endif //CONFIGURATION_ADV_H

76
Marlin/example_configurations/delta/generic/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -287,44 +286,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -367,6 +359,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -400,17 +393,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define Z_MAX_POS MANUAL_Z_HOME_POS
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -431,7 +427,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -642,7 +638,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -662,9 +658,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/delta/generic/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -259,7 +262,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -356,7 +358,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

76
Marlin/example_configurations/delta/kossel_mini/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -287,44 +286,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -367,6 +359,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -400,17 +393,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS MANUAL_Z_HOME_POS
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -431,7 +427,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -646,7 +642,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -666,9 +662,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {10, 10, 20} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

77
Marlin/example_configurations/makibox/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -257,44 +256,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -337,6 +329,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define E_ENABLE_ON 0 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -370,17 +363,19 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#define Z_MAX_POS 86
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -401,7 +396,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -593,7 +588,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -613,9 +608,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = false; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/makibox/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

76
Marlin/example_configurations/tvrrug/Round2/Configuration.h

@ -1,4 +1,4 @@
#ifndef CONFIGURATION_H
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "boards.h"
@ -39,7 +39,6 @@ Here are some standard links for getting your machine calibrated:
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
// build by the user have been successfully uploaded into firmware.
#define STRING_VERSION "1.0.3 dev"
#define STRING_URL "reprap.org"
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
#define STRING_SPLASH_LINE1 "v" STRING_VERSION // will be shown during bootup in line 1
@ -259,44 +258,37 @@ Here are some standard links for getting your machine calibrated:
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
//===========================================================================
//============================= Thermal Runaway Protection ==================
//======================== Thermal Runaway Protection =======================
//===========================================================================
/*
This is a feature to protect your printer from burn up in flames if it has
a thermistor coming off place (this happened to a friend of mine recently and
motivated me writing this feature).
The issue: If a thermistor come off, it will read a lower temperature than actual.
The system will turn the heater on forever, burning up the filament and anything
else around.
After the temperature reaches the target for the first time, this feature will
start measuring for how long the current temperature stays below the target
minus _HYSTERESIS (set_temperature - THERMAL_RUNAWAY_PROTECTION_HYSTERESIS).
If it stays longer than _PERIOD, it means the thermistor temperature
cannot catch up with the target, so something *may be* wrong. Then, to be on the
safe side, the system will he halt.
Bear in mind the count down will just start AFTER the first time the
thermistor temperature is over the target, so you will have no problem if
your extruder heater takes 2 minutes to hit the target on heating.
/**
* Thermal Runaway Protection protects your printer from damage and fire if a
* thermistor falls out or temperature sensors fail in any way.
*
* The issue: If a thermistor falls out or a temperature sensor fails,
* Marlin can no longer sense the actual temperature. Since a disconnected
* thermistor reads as a low temperature, the firmware will keep the heater on.
*
* The solution: Once the temperature reaches the target, start observing.
* If the temperature stays too far below the target (hysteresis) for too long,
* the firmware will halt as a safety precaution.
*
* Note that because the countdown starts only AFTER the temperature reaches
* the target, this will not catch a thermistor that is already disconnected
* when the print starts!
*
* To enable for all extruder heaters, uncomment the two defines below:
*/
// If you want to enable this feature for all your extruder heaters,
// uncomment the 2 defines below:
// Parameters for all extruder heaters
//#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_PERIOD 40 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_HYSTERESIS 4 // in degree Celsius
// If you want to enable this feature for your bed heater,
// uncomment the 2 defines below:
// To enable for the bed heater, uncomment the two defines below:
// Parameters for the bed heater
//#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 //in seconds
//#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
#define THERMAL_RUNAWAY_PROTECTION_BED_PERIOD 20 // in seconds
#define THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS 2 // in degree Celsius
//===========================================================================
//============================= Mechanical Settings =========================
@ -339,6 +331,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define E_ENABLE_ON 1 // For all extruders
// Disables axis when it's not being used.
// WARNING: When motors turn off there is a chance of losing position accuracy!
#define DISABLE_X false
#define DISABLE_Y false
#define DISABLE_Z false
@ -372,17 +365,20 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#define Z_MAX_POS 120
//===========================================================================
//============================= Filament Runout Sensor ======================
//========================= Filament Runout Sensor ==========================
//===========================================================================
//#define FILAMENT_RUNOUT_SENSOR // Uncomment for defining a filament runout sensor such as a mechanical or opto endstop to check the existence of filament
// In RAMPS uses servo pin 2. Can be changed in pins file. For other boards pin definition should be made.
// It is assumed that when logic high = filament available
// when logic low = filament ran out
//const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
//#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#ifdef FILAMENT_RUNOUT_SENSOR
const bool FIL_RUNOUT_INVERTING = true; // Should be uncommented and true or false should assigned
#define ENDSTOPPULLUP_FIL_RUNOUT // Uncomment to use internal pullup for filament runout pins if the sensor is defined.
#define FILAMENT_RUNOUT_SCRIPT "M600"
#endif
//===========================================================================
//============================ Manual Bed Leveling ==========================
//=========================== Manual Bed Leveling ===========================
//===========================================================================
// #define MANUAL_BED_LEVELING // Add display menu option for bed leveling
@ -403,7 +399,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
#endif // MESH_BED_LEVELING
//===========================================================================
//============================= Bed Auto Leveling ===========================
//============================ Bed Auto Leveling ============================
//===========================================================================
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
@ -599,7 +595,7 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//==============================LCD and SD support=============================
// Define your display language below. Replace (en) with your language code and uncomment.
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, test
// en, pl, fr, de, es, ru, it, pt, pt-br, fi, an, nl, ca, eu, kana, kana_utf8, cn, test
// See also language.h
//#define LANGUAGE_INCLUDE GENERATE_LANGUAGE_INCLUDE(en)
@ -619,9 +615,9 @@ const bool Z_PROBE_ENDSTOP_INVERTING = true; // set to true to invert the logic
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
// 0 to disable buzzer feedback
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
// 0 to disable buzzer feedback. Test with M300 S<frequency Hz> P<duration ms>
// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3)
// http://reprap.org/wiki/PanelOne

6
Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h

@ -195,6 +195,9 @@
#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate)
//#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
// When G28 is called, this option will make Y home before X
// #define HOME_Y_BEFORE_X
// @section machine
#define AXIS_RELATIVE_MODES {false, false, false, false}
@ -258,7 +261,6 @@
#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_DEBUG // If defined, output the encoder steps per second 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
@ -355,7 +357,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//#define HEATERS_PARALLEL
//===========================================================================
//=============================Buffers ============================
//================================= Buffers =================================
//===========================================================================
// @section hidden

BIN
Marlin/fonts/ISO10646_CN.fon

Binary file not shown.

22
Marlin/fonts/README.fonts

@ -3,4 +3,24 @@ In Fony export the fonts to bdf-format. Maybe another one can edit them with Fon
Then run make_fonts.bat what calls bdf2u8g.exe with the needed parameters to produce the .h files.
The .h files must be edited to replace '#include "u8g.h"' with '#include <utility/u8g.h>', replace 'U8G_FONT_SECTION' with 'U8G_SECTION', insert '.progmem.' right behind the first '"' and moved to the main directory.
Especially the Kana and Cyrillic fonts should be revised by someone who knows what he/she does. I am only a west-European with very little knowledge about this scripts.
How to integrate a new font:
Currently we are limited to 256 symbols per font. We use a menu system with 5 lines, on a display with 64 pixel height. That means we have 12 pixel for a line. To have some space in between the lines we can't use more then 10 pixel height for the symbols. For up to 11 pixel set TALL_FONT_CORRECTION 1 when loading the font.
To fit 22 Symbols on the 128 pixel wide screen, the symbols can't be wider than 5 pixel, for the first 128 symbols.
For the second half of the font we now support up to 11x11 pixel.
* Get 'Fony.exe'
* Copy one of the existing *.fon files and work with this.
* Change the pixels. Don't change width or height.
* Export as *.bdf
* Use 'bdf2u8g.exe' to produce the *.h file. Examples for the existing fonts are in 'make_fonts.bat'
* Edit the produced .h file to match our needs. See hints in 'README.fonts' or the other 'dogm_font_data_.h' files.
* Make a new entry in the font list in 'dogm_lcd_implementation.h' before the '#else // fall back'
#elif defined( DISPLAY_CHARSET_NEWNAME )
#include "dogm_font_data_yourfont.h"
#define FONT_MENU_NAME YOURFONTNAME
#else // fall-back
* Add your font to the list of permitted fonts in 'language_en.h'
... || defined(DISPLAY_CHARSET_YOUR_NEW_FONT) ... )
Especially the Kana font should be revised by someone who knows what he/she does. I am only a west-European with very little knowledge about this script.

1
Marlin/fonts/make_fonts.bat

@ -5,3 +5,4 @@
.\bdf2u8g.exe -b 32 -e 255 ISO10646-1.bdf ISO10646_1_5x7 dogm_font_data_ISO10646_1.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646_5_Cyrillic.bdf ISO10646_5_Cyrillic_5x7 dogm_font_data_ISO10646_5_Cyrillic.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646_Kana.bdf ISO10646_Kana_5x7 dogm_font_data_ISO10646_Kana.h
.\bdf2u8g.exe -b 32 -e 255 ISO10646_CN.bdf ISO10646_CN dogm_font_data_ISO10646_CN.h

23
Marlin/language.h

@ -30,6 +30,7 @@
// eu Basque-Euskera
// kana Japanese
// kana_utf Japanese
// cn Chinese
#ifndef LANGUAGE_INCLUDE
// pick your language from the list above
@ -130,13 +131,15 @@
#define MSG_FILE_PRINTED "Done printing file"
#define MSG_BEGIN_FILE_LIST "Begin file list"
#define MSG_END_FILE_LIST "End file list"
#define MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
#define MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
#define MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
#define MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
#define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_M104_INVALID_EXTRUDER "M104 " MSG_INVALID_EXTRUDER " "
#define MSG_M105_INVALID_EXTRUDER "M105 " MSG_INVALID_EXTRUDER " "
#define MSG_M109_INVALID_EXTRUDER "M109 " MSG_INVALID_EXTRUDER " "
#define MSG_M200_INVALID_EXTRUDER "M200 " MSG_INVALID_EXTRUDER " "
#define MSG_M218_INVALID_EXTRUDER "M218 " MSG_INVALID_EXTRUDER " "
#define MSG_M221_INVALID_EXTRUDER "M221 " MSG_INVALID_EXTRUDER " "
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
#define MSG_HEATING "Heating..."
#define MSG_HEATING_COMPLETE "Heating done."
#define MSG_BED_HEATING "Bed Heating."
@ -148,8 +151,6 @@
#define MSG_RESEND "Resend: "
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
#define MSG_INVALID_EXTRUDER "Invalid extruder"
#define MSG_INVALID_SOLENOID "Invalid solenoid"
#define MSG_X_MIN "x_min: "
#define MSG_X_MAX "x_max: "
#define MSG_Y_MIN "y_min: "
@ -158,6 +159,10 @@
#define MSG_Z_MAX "z_max: "
#define MSG_Z2_MAX "z2_max: "
#define MSG_Z_PROBE "z_probe: "
#define MSG_ERR_MATERIAL_INDEX "M145 S<index> out of range (0-1)"
#define MSG_ERR_M421_REQUIRES_XYZ "M421 requires XYZ parameters"
#define MSG_ERR_MESH_INDEX_OOB "Mesh XY index is out of bounds"
#define MSG_ERR_M428_TOO_FAR "Too far from reference point"
#define MSG_M119_REPORT "Reporting endstop status"
#define MSG_ENDSTOP_HIT "TRIGGERED"
#define MSG_ENDSTOP_OPEN "open"
@ -210,7 +215,7 @@
#define MSG_OK_B "ok B:"
#define MSG_OK_T "ok T:"
#define MSG_AT " @:"
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from above into Configuration.h"
#define MSG_PID_AUTOTUNE_FINISHED MSG_PID_AUTOTUNE " finished! Put the last Kp, Ki and Kd constants from below into Configuration.h"
#define MSG_PID_DEBUG " PID_DEBUG "
#define MSG_PID_DEBUG_INPUT ": Input "
#define MSG_PID_DEBUG_OUTPUT " Output "

159
Marlin/language_cn.h

@ -0,0 +1,159 @@
/**
* Chinese
*
* LCD Menu Messages
* Se also documentation/LCDLanguageFont.md
*
*/
#ifndef LANGUAGE_CN_H
#define LANGUAGE_CN_H
#define MAPPER_NON // For direct asci codes
#define DISPLAY_CHARSET_ISO10646_CN
#define WELCOME_MSG "\xa4\xa5\xa6\xa7"
#define MSG_SD_INSERTED "\xa8\xa9\xaa\xab"
#define MSG_SD_REMOVED "\xa8\xa9\xac\xad"
#define MSG_MAIN "\xae\xaf\xb0"
#define MSG_AUTOSTART "\xb1\xb2\xb3\xb4"
#define MSG_DISABLE_STEPPERS "\xb5\xb6\xb7\xb8\xb9\xba"
#define MSG_AUTO_HOME "\xbb\xbc\xbd"
#define MSG_SET_HOME_OFFSETS "\xbe\xbf\xbb\xbc\xbd\xc0\xc1"
#define MSG_SET_ORIGIN "\xbe\xbf\xbc\xbd"
#define MSG_PREHEAT_PLA "\xc3\xc4 PLA"
#define MSG_PREHEAT_PLA_N MSG_PREHEAT_PLA " "
#define MSG_PREHEAT_PLA_ALL MSG_PREHEAT_PLA " \xc5\xc6"
#define MSG_PREHEAT_PLA_BEDONLY MSG_PREHEAT_PLA " \xc4\xc7"
#define MSG_PREHEAT_PLA_SETTINGS MSG_PREHEAT_PLA " \xbe\xbf"
#define MSG_PREHEAT_ABS "\xc3\xc4 ABS"
#define MSG_PREHEAT_ABS_N MSG_PREHEAT_ABS " "
#define MSG_PREHEAT_ABS_ALL MSG_PREHEAT_ABS " \xc5\xc6"
#define MSG_PREHEAT_ABS_BEDONLY MSG_PREHEAT_ABS " \xbe\xc6"
#define MSG_PREHEAT_ABS_SETTINGS MSG_PREHEAT_ABS " \xbe\xbf"
#define MSG_H1 "1"
#define MSG_H2 "2"
#define MSG_H3 "3"
#define MSG_H4 "4"
#define MSG_COOLDOWN "\xc8\xc9"
#define MSG_SWITCH_PS_ON "\xb9\xcb\xca\xb3"
#define MSG_SWITCH_PS_OFF "\xb9\xcb\xb5\xb6"
#define MSG_EXTRUDE "\xcc\xad"
#define MSG_RETRACT "\xbb\xcd"
#define MSG_MOVE_AXIS "\xc1\xb2\xce"
#define MSG_LEVEL_BED "\xcf\xe0\xc4\xc7"
#define MSG_MOVE_X "\xc1\xb2 X"
#define MSG_MOVE_Y "\xc1\xb2 Y"
#define MSG_MOVE_Z "\xc1\xb2 Z"
#define MSG_MOVE_E "\xcc\xad\xba"
#define MSG_MOVE_01MM "\xc1\xb2 0.1mm"
#define MSG_MOVE_1MM "\xc1\xb2 1mm"
#define MSG_MOVE_10MM "\xc1\xb2 10mm"
#define MSG_SPEED "\xd1\xd2"
#define MSG_NOZZLE "\xd3\xd4"
#define MSG_N2 " 2"
#define MSG_N3 " 3"
#define MSG_N4 " 4"
#define MSG_BED "\xc4\xc7"
#define MSG_FAN_SPEED "\xd5\xd6\xd1\xd2"
#define MSG_FLOW "\xcc\xad\xd1\xd2"
#define MSG_F0 " 0"
#define MSG_F1 " 1"
#define MSG_F2 " 2"
#define MSG_F3 " 3"
#define MSG_CONTROL "\xd8\xd9"
#define MSG_MIN LCD_STR_THERMOMETER " \xda\xdb"
#define MSG_MAX LCD_STR_THERMOMETER " \xda\xdc"
#define MSG_FACTOR LCD_STR_THERMOMETER " \xdd\xde"
#define MSG_AUTOTEMP "\xb1\xb2\xd8\xc9"
#define MSG_ON "\xb3 " // intentional space to shift wide symbol to the left
#define MSG_OFF "\xb5 " // intentional space to shift wide symbol to the left
#define MSG_PID_P "PID-P"
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_E2 " E2"
#define MSG_E3 " E3"
#define MSG_E4 " E4"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "x"
#define MSG_Y "y"
#define MSG_Z "z"
#define MSG_E "e"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
#define MSG_A_RETRACT "A-retract"
#define MSG_A_TRAVEL "A-travel"
#define MSG_XSTEPS "Xsteps/mm"
#define MSG_YSTEPS "Ysteps/mm"
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#define MSG_TEMPERATURE "\xc9\xd2"
#define MSG_MOTION "\xdf\xb2"
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E in mm3"
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Fil. Dia. 3"
#define MSG_FILAMENT_SIZE_EXTRUDER_3 "Fil. Dia. 4"
#define MSG_CONTRAST "LCD contrast"
#define MSG_STORE_EPROM "Store memory"
#define MSG_LOAD_EPROM "Load memory"
#define MSG_RESTORE_FAILSAFE "Restore failsafe"
#define MSG_REFRESH "Refresh"
#define MSG_WATCH "\xec\xed\xee\xef"
#define MSG_PREPARE "\xa4\xa5"
#define MSG_TUNE "\xcf\xf0"
#define MSG_PAUSE_PRINT "\xf1\xf2\xca\xf3"
#define MSG_RESUME_PRINT "\xf4\xf5\xca\xf3"
#define MSG_STOP_PRINT "\xf2\xf6\xca\xf3"
#define MSG_CARD_MENU "\xaf\xb0"
#define MSG_NO_CARD "\xf9\xa8"
#define MSG_DWELL "Sleep..."
#define MSG_USERWAIT "Wait for user..."
#define MSG_RESUMING "Resuming print"
#define MSG_PRINT_ABORTED "Print aborted"
#define MSG_NO_MOVE "No move."
#define MSG_KILLED "KILLED. "
#define MSG_STOPPED "STOPPED. "
#define MSG_CONTROL_RETRACT "Retract mm"
#define MSG_CONTROL_RETRACT_SWAP "Swap Re.mm"
#define MSG_CONTROL_RETRACTF "Retract V"
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#define MSG_CONTROL_RETRACT_RECOVER_SWAP "S UnRet+mm"
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet V"
#define MSG_AUTORETRACT "AutoRetr."
#define MSG_FILAMENTCHANGE "Change filament"
#define MSG_INIT_SDCARD "Init. SD card"
#define MSG_CNG_SDCARD "Change SD card"
#define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_HEATING_FAILED_LCD "Heating failed"
#define MSG_ERR_REDUNDANT_TEMP "Err: REDUNDANT TEMP ERROR"
#define MSG_THERMAL_RUNAWAY "THERMAL RUNAWAY"
#define MSG_ERR_MAXTEMP "Err: MAXTEMP"
#define MSG_ERR_MINTEMP "Err: MINTEMP"
#define MSG_ERR_MAXTEMP_BED "Err: MAXTEMP BED"
#define MSG_END_HOUR "hours"
#define MSG_END_MINUTE "minutes"
#ifdef DELTA_CALIBRATION_MENU
#define MSG_DELTA_CALIBRATE "Delta Calibration"
#define MSG_DELTA_CALIBRATE_X "Calibrate X"
#define MSG_DELTA_CALIBRATE_Y "Calibrate Y"
#define MSG_DELTA_CALIBRATE_Z "Calibrate Z"
#define MSG_DELTA_CALIBRATE_CENTER "Calibrate Center"
#endif // DELTA_CALIBRATION_MENU
#endif // LANGUAGE_CN_H

14
Marlin/language_de.h

@ -13,7 +13,7 @@
//#define SIMULATE_ROMFONT
#define DISPLAY_CHARSET_ISO10646_1
#define WELCOME_MSG MACHINE_NAME " Bereit."
#define WELCOME_MSG MACHINE_NAME " bereit."
#define MSG_SD_INSERTED "SDKarte erkannt."
#define MSG_SD_REMOVED "SDKarte entfernt."
#define MSG_MAIN "Hauptmenü"
@ -61,9 +61,9 @@
#define MSG_PID_D "PID D"
#define MSG_PID_C "PID C"
#define MSG_ACC "A"
#define MSG_VXY_JERK "V xy jerk"
#define MSG_VZ_JERK "V z jerk"
#define MSG_VE_JERK "V e jerk"
#define MSG_VXY_JERK "V xy Ruck"
#define MSG_VZ_JERK "V z Ruck"
#define MSG_VE_JERK "V e Ruck"
#define MSG_VMAX "V max " // space by purpose
#define MSG_X "x"
#define MSG_Y "y"
@ -84,7 +84,7 @@
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Filament D 1"
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Filament D 2"
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Filament D 3"
#define MSG_CONTRAST "LCD contrast"
#define MSG_CONTRAST "LCD Kontrast"
#define MSG_STORE_EPROM "EPROM speichern"
#define MSG_LOAD_EPROM "EPROM laden"
#define MSG_RESTORE_FAILSAFE "Standardkonfig."
@ -116,7 +116,7 @@
#define MSG_INIT_SDCARD "SDKarte erkennen"// Manually initialize the SD-card via user interface
#define MSG_CNG_SDCARD "SDKarte erkennen"// SD-card changed by user. For machines with no autocarddetect. Both send "M21"
#define MSG_ZPROBE_OUT "Sensor ausserhalb"
#define MSG_POSITION_UNKNOWN "X/Y vor Z Homen."
#define MSG_POSITION_UNKNOWN "X/Y vor Z homen."
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y"
@ -126,7 +126,7 @@
#define MSG_END_MINUTE "Minuten"
#ifdef DELTA_CALIBRATION_MENU
#define MSG_DELTA_CALIBRATE "Delta Kalibrieren"
#define MSG_DELTA_CALIBRATE "Delta kalibrieren"
#define MSG_DELTA_CALIBRATE_X "Kalibriere X"
#define MSG_DELTA_CALIBRATE_Y "Kalibriere Y"
#define MSG_DELTA_CALIBRATE_Z "Kalibriere Z"

2
Marlin/language_en.h

@ -13,7 +13,7 @@
#endif
//#define SIMULATE_ROMFONT //Comment in to see what is seen on the character based displays
#if !( defined(SIMULATE_ROMFONT)|| defined(DISPLAY_CHARSET_ISO10646_1)|| defined(DISPLAY_CHARSET_ISO10646_5)|| defined(DISPLAY_CHARSET_ISO10646_KANA) )
#if !( defined(SIMULATE_ROMFONT)|| defined(DISPLAY_CHARSET_ISO10646_1)|| defined(DISPLAY_CHARSET_ISO10646_5)|| defined(DISPLAY_CHARSET_ISO10646_KANA)|| defined(DISPLAY_CHARSET_ISO10646_CN) )
#define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays.
#endif

2
Marlin/pins.h

@ -76,6 +76,8 @@
#include "pins_PRINTRBOARD.h"
#elif MB(BRAINWAVE)
#include "pins_BRAINWAVE.h"
#elif MB(BRAINWAVE_PRO)
#include "pins_BRAINWAVE_PRO.h"
#elif MB(SAV_MKI)
#include "pins_SAV_MKI.h"
#elif MB(TEENSY2)

4
Marlin/pins_AZTEEG_X3.h

@ -28,9 +28,7 @@
#define STAT_LED_RED 64
#define STAT_LED_BLUE 63
#endif
#endif
#elif define TEMP_STAT_LEDS
#elif defined(TEMP_STAT_LEDS)
#define STAT_LED_RED 6
#define STAT_LED_BLUE 11
#endif

63
Marlin/pins_BRAINWAVE_PRO.h

@ -0,0 +1,63 @@
/**
* Brainwave Pro pin assignments (AT90USB186)
*
* Requires hardware bundle for Arduino:
* https://github.com/unrepentantgeek/brainwave-arduino
*/
#ifndef __AVR_AT90USB1286__
#error Oops! Make sure you have 'Brainwave Pro' selected from the 'Tools -> Boards' menu.
#endif
#ifndef AT90USBxx_TEENSYPP_ASSIGNMENTS // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical.
#error Uncomment #define AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h for this config
#endif
#define AT90USB 1286 // Disable MarlinSerial etc.
#define X_STEP_PIN 33
#define X_DIR_PIN 32
#define X_ENABLE_PIN 11
#define X_STOP_PIN 47
#define Y_STEP_PIN 31
#define Y_DIR_PIN 30
#define Y_ENABLE_PIN 8
#define Y_STOP_PIN 18
#define Z_STEP_PIN 29
#define Z_DIR_PIN 28
#define Z_ENABLE_PIN 37
#define Z_MAX_PIN 36
#define Z_MIN_PIN 17 // Bed probe
#define E0_STEP_PIN 35
#define E0_DIR_PIN 34
#define E0_ENABLE_PIN 13
#define HEATER_0_PIN 15
#define HEATER_1_PIN -1
#define HEATER_2_PIN -1
#define HEATER_BED_PIN 14 // Bed
#define FAN_PIN 16 // Fan, PWM
#define TEMP_0_PIN 2 // Extruder / Analog pin numbering
#define TEMP_1_PIN 1 // Spare / Analog pin numbering
#define TEMP_2_PIN -1
#define TEMP_BED_PIN 0 // Bed / Analog pin numbering
#define SDPOWER -1
#define SDSS 20
#define LED_PIN 19
#define PS_ON_PIN -1
#define KILL_PIN -1
#define ALARM_PIN -1
#define SDCARDDETECT 12
#ifndef SDSUPPORT
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 21
#define MISO_PIN 23
#define MOSI_PIN 22
#endif

2
Marlin/pins_SAV_MKI.h

@ -82,7 +82,7 @@
#define HOME_PIN -1 // A4 = marlin 44 - teensy = 42
#ifdef NUM_SERVOS
#define SERVO0_PIN 41 // In teensy's pin definition for pinMode (in Servo.cpp)
#define SERVO0_PIN 41 // In teensy's pin definition for pinMode (in servo.cpp)
#endif
#endif // SAV_3DLCD

147
Marlin/planner.cpp

@ -1,54 +1,51 @@
/*
planner.c - buffers movement commands and manages the acceleration profile plan
Part of Grbl
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl 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.
Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
/* The ring buffer implementation gleaned from the wiring_serial library by David A. Mellis. */
/*
Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
s == speed, a == acceleration, t == time, d == distance
Basic definitions:
Speed[s_, a_, t_] := s + (a*t)
Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
Distance to reach a specific speed with a constant acceleration:
Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
Speed after a given distance of travel with constant acceleration:
Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
m -> Sqrt[2 a d + s^2]
DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
When to start braking (di) to reach a specified destionation speed (s2) after accelerating
from initial speed s1 without ever stopping at a plateau:
Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
/**
* planner.cpp - Buffer movement commands and manage the acceleration profile plan
* Part of Grbl
*
* Copyright (c) 2009-2011 Simen Svale Skogsrud
*
* Grbl 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.
*
* Grbl 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 Grbl. If not, see <http://www.gnu.org/licenses/>.
*
*
* The ring buffer implementation gleaned from the wiring_serial library by David A. Mellis.
*
*
* Reasoning behind the mathematics in this module (in the key of 'Mathematica'):
*
* s == speed, a == acceleration, t == time, d == distance
*
* Basic definitions:
* Speed[s_, a_, t_] := s + (a*t)
* Travel[s_, a_, t_] := Integrate[Speed[s, a, t], t]
*
* Distance to reach a specific speed with a constant acceleration:
* Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, d, t]
* d -> (m^2 - s^2)/(2 a) --> estimate_acceleration_distance()
*
* Speed after a given distance of travel with constant acceleration:
* Solve[{Speed[s, a, t] == m, Travel[s, a, t] == d}, m, t]
* m -> Sqrt[2 a d + s^2]
*
* DestinationSpeed[s_, a_, d_] := Sqrt[2 a d + s^2]
*
* When to start braking (di) to reach a specified destination speed (s2) after accelerating
* from initial speed s1 without ever stopping at a plateau:
* Solve[{DestinationSpeed[s1, a, di] == DestinationSpeed[s2, a, d - di]}, di]
* di -> (2 a d - s1^2 + s2^2)/(4 a) --> intersection_distance()
*
* IntersectionDistance[s1_, s2_, a_, d_] := (2 a d - s1^2 + s2^2)/(4 a)
*
*/
#include "Marlin.h"
@ -71,17 +68,17 @@ float max_feedrate[NUM_AXIS]; // Max speeds in mm per minute
float axis_steps_per_unit[NUM_AXIS];
unsigned long max_acceleration_units_per_sq_second[NUM_AXIS]; // Use M201 to override by software
float minimumfeedrate;
float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all printing moves. M204 SXXXX
float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
float travel_acceleration; // Travel acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
float acceleration; // Normal acceleration mm/s^2 DEFAULT ACCELERATION for all printing moves. M204 SXXXX
float retract_acceleration; // Retract acceleration mm/s^2 filament pull-back and push-forward while standing still in the other axes M204 TXXXX
float travel_acceleration; // Travel acceleration mm/s^2 DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
float max_xy_jerk; // The largest speed change requiring no acceleration
float max_z_jerk;
float max_e_jerk;
float mintravelfeedrate;
unsigned long axis_steps_per_sqr_second[NUM_AXIS];
#ifdef ENABLE_AUTO_BED_LEVELING
// this holds the required transform to compensate for bed level
// Transform required to compensate for bed level
matrix_3x3 plan_bed_level_matrix = {
1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
@ -89,11 +86,6 @@ unsigned long axis_steps_per_sqr_second[NUM_AXIS];
};
#endif // ENABLE_AUTO_BED_LEVELING
// The current position of the tool in absolute steps
long position[NUM_AXIS]; //rescaled from extern when axis_steps_per_unit are changed by gcode
static float previous_speed[NUM_AXIS]; // Speed of previous path line segment
static float previous_nominal_speed; // Nominal speed of previous path line segment
#ifdef AUTOTEMP
float autotemp_max = 250;
float autotemp_min = 210;
@ -101,18 +93,25 @@ static float previous_nominal_speed; // Nominal speed of previous path line segm
bool autotemp_enabled = false;
#endif
unsigned char g_uc_extruder_last_move[4] = {0,0,0,0};
//===========================================================================
//=================semi-private variables, used in inline functions =====
//============ semi-private variables, used in inline functions =============
//===========================================================================
block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instfructions
volatile unsigned char block_buffer_head; // Index of the next block to be pushed
volatile unsigned char block_buffer_tail; // Index of the block to process now
//===========================================================================
//=============================private variables ============================
//============================ private variables ============================
//===========================================================================
// The current position of the tool in absolute steps
long position[NUM_AXIS]; // Rescaled from extern when axis_steps_per_unit are changed by gcode
static float previous_speed[NUM_AXIS]; // Speed of previous path line segment
static float previous_nominal_speed; // Nominal speed of previous path line segment
unsigned char g_uc_extruder_last_move[4] = {0,0,0,0};
#ifdef XY_FREQUENCY_LIMIT
// Used for the frequency limit
#define MAX_FREQ_TIME (1000000.0/XY_FREQUENCY_LIMIT)
@ -126,15 +125,15 @@ volatile unsigned char block_buffer_tail; // Index of the block to pro
static char meas_sample; //temporary variable to hold filament measurement sample
#endif
//===========================================================================
//================================ functions ================================
//===========================================================================
// Get the next / previous index of the next block in the ring buffer
// NOTE: Using & here (not %) because BLOCK_BUFFER_SIZE is always a power of 2
FORCE_INLINE int8_t next_block_index(int8_t block_index) { return BLOCK_MOD(block_index + 1); }
FORCE_INLINE int8_t prev_block_index(int8_t block_index) { return BLOCK_MOD(block_index - 1); }
//===========================================================================
//================================ Functions ================================
//===========================================================================
// Calculates the distance (not time) it takes to accelerate from initial_rate to target_rate using the
// given acceleration:
FORCE_INLINE float estimate_acceleration_distance(float initial_rate, float target_rate, float acceleration) {
@ -960,7 +959,7 @@ float junction_deviation = 0.1;
vector_3 position = vector_3(st_get_position_mm(X_AXIS), st_get_position_mm(Y_AXIS), st_get_position_mm(Z_AXIS));
//position.debug("in plan_get position");
//plan_bed_level_matrix.debug("in plan_get bed_level");
//plan_bed_level_matrix.debug("in plan_get_position");
matrix_3x3 inverse = matrix_3x3::transpose(plan_bed_level_matrix);
//inverse.debug("in plan_get inverse");
position.apply_rotation(inverse);
@ -982,10 +981,10 @@ float junction_deviation = 0.1;
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
#endif
float nx = position[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]);
float ny = position[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]);
float nz = position[Z_AXIS] = lround(z * axis_steps_per_unit[Z_AXIS]);
float ne = position[E_AXIS] = lround(e * axis_steps_per_unit[E_AXIS]);
float nx = position[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]),
ny = position[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]),
nz = position[Z_AXIS] = lround(z * axis_steps_per_unit[Z_AXIS]),
ne = position[E_AXIS] = lround(e * axis_steps_per_unit[E_AXIS]);
st_set_position(nx, ny, nz, ne);
previous_nominal_speed = 0.0; // Resets planner junction speeds. Assumes start from rest.

14
Marlin/planner.h

@ -115,15 +115,19 @@ FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block
void plan_set_e_position(const float &e);
//===========================================================================
//============================= public variables ============================
//===========================================================================
extern millis_t minsegmenttime;
extern float max_feedrate[NUM_AXIS]; // set the max speeds
extern float max_feedrate[NUM_AXIS]; // Max speeds in mm per minute
extern float axis_steps_per_unit[NUM_AXIS];
extern unsigned long max_acceleration_units_per_sq_second[NUM_AXIS]; // Use M201 to override by software
extern float minimumfeedrate;
extern float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX
extern float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX
extern float travel_acceleration; // Travel acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
extern float max_xy_jerk; //speed than can be stopped at once, if i understand correctly.
extern float acceleration; // Normal acceleration mm/s^2 DEFAULT ACCELERATION for all printing moves. M204 SXXXX
extern float retract_acceleration; // Retract acceleration mm/s^2 filament pull-back and push-forward while standing still in the other axes M204 TXXXX
extern float travel_acceleration; // Travel acceleration mm/s^2 DEFAULT ACCELERATION for all NON printing moves. M204 MXXXX
extern float max_xy_jerk; // The largest speed change requiring no acceleration
extern float max_z_jerk;
extern float max_e_jerk;
extern float mintravelfeedrate;

4
Marlin/Servo.cpp → Marlin/servo.cpp

@ -1,5 +1,5 @@
/*
Servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
servo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
@ -48,7 +48,7 @@
#include <avr/interrupt.h>
#include <Arduino.h>
#include "Servo.h"
#include "servo.h"
#define usToTicks(_us) (( clockCyclesPerMicrosecond()* _us) / 8) // converts microseconds to tick (assumes prescale of 8) // 12 Aug 2009
#define ticksToUs(_ticks) (( (unsigned)_ticks * 8)/ clockCyclesPerMicrosecond() ) // converts from ticks back to microseconds

6
Marlin/Servo.h → Marlin/servo.h

@ -1,5 +1,5 @@
/*
Servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
servo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 2
Copyright (c) 2009 Michael Margolis. All right reserved.
This library is free software; you can redistribute it and/or
@ -42,8 +42,8 @@
detach() - Stops an attached servos from pulsing its i/o pin.
*/
#ifndef Servo_h
#define Servo_h
#ifndef servo_h
#define servo_h
#include <inttypes.h>

104
Marlin/stepper.cpp

@ -54,7 +54,7 @@ static unsigned int cleaning_buffer_counter;
locked_z2_motor = false;
#endif
// Counter variables for the bresenham line tracer
// Counter variables for the Bresenham line tracer
static long counter_x, counter_y, counter_z, counter_e;
volatile static unsigned long step_events_completed; // The number of step events executed in the current block
@ -66,7 +66,7 @@ volatile static unsigned long step_events_completed; // The number of step event
static long acceleration_time, deceleration_time;
//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
static unsigned short acc_step_rate; // needed for deccelaration start point
static unsigned short acc_step_rate; // needed for deceleration start point
static char step_loops;
static unsigned short OCR1A_nominal;
static unsigned short step_loops_nominal;
@ -205,8 +205,14 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
// intRes = longIn1 * longIn2 >> 24
// uses:
// r26 to store 0
// r27 to store the byte 1 of the 48bit result
#define MultiU24X24toH16(intRes, longIn1, longIn2) \
// r27 to store bits 16-23 of the 48bit result. The top bit is used to round the two byte result.
// note that the lower two bytes and the upper byte of the 48bit result are not calculated.
// this can cause the result to be out by one as the lower bytes may cause carries into the upper ones.
// B0 A0 are bits 24-39 and are the returned value
// C1 B1 A1 is longIn1
// D2 C2 B2 A2 is longIn2
//
#define MultiU24X32toH16(intRes, longIn1, longIn2) \
asm volatile ( \
"clr r26 \n\t" \
"mul %A1, %B2 \n\t" \
@ -237,6 +243,11 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
"lsr r27 \n\t" \
"adc %A0, r26 \n\t" \
"adc %B0, r26 \n\t" \
"mul %D2, %A1 \n\t" \
"add %A0, r0 \n\t" \
"adc %B0, r1 \n\t" \
"mul %D2, %B1 \n\t" \
"add %B0, r0 \n\t" \
"clr r1 \n\t" \
: \
"=&r" (intRes) \
@ -313,7 +324,7 @@ void enable_endstops(bool check) { check_endstops = check; }
// The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
// first block->accelerate_until step_events_completed, then keeps going at constant speed until
// step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
// The slope of acceleration is calculated with the leib ramp alghorithm.
// The slope of acceleration is calculated using v = u + at where t is the accumulated timer values of the steps so far.
void st_wake_up() {
// TCNT1 = 0;
@ -452,14 +463,22 @@ ISR(TIMER1_COMPA_vect) {
count_direction[Y_AXIS] = 1;
}
#define _ENDSTOP(axis, minmax) axis ##_## minmax ##_endstop
#define _ENDSTOP_PIN(AXIS, MINMAX) AXIS ##_## MINMAX ##_PIN
#define _ENDSTOP_INVERTING(AXIS, MINMAX) AXIS ##_## MINMAX ##_ENDSTOP_INVERTING
#define _OLD_ENDSTOP(axis, minmax) old_## axis ##_## minmax ##_endstop
#define _AXIS(AXIS) AXIS ##_AXIS
#define _ENDSTOP_HIT(axis) endstop_## axis ##_hit
#define UPDATE_ENDSTOP(axis,AXIS,minmax,MINMAX) \
bool axis ##_## minmax ##_endstop = (READ(AXIS ##_## MINMAX ##_PIN) != AXIS ##_## MINMAX ##_ENDSTOP_INVERTING); \
if (axis ##_## minmax ##_endstop && old_## axis ##_## minmax ##_endstop && (current_block->steps[AXIS ##_AXIS] > 0)) { \
endstops_trigsteps[AXIS ##_AXIS] = count_position[AXIS ##_AXIS]; \
endstop_## axis ##_hit = true; \
bool _ENDSTOP(axis, minmax) = (READ(_ENDSTOP_PIN(AXIS, MINMAX)) != _ENDSTOP_INVERTING(AXIS, MINMAX)); \
if (_ENDSTOP(axis, minmax) && _OLD_ENDSTOP(axis, minmax) && (current_block->steps[_AXIS(AXIS)] > 0)) { \
endstops_trigsteps[_AXIS(AXIS)] = count_position[_AXIS(AXIS)]; \
_ENDSTOP_HIT(axis) = true; \
step_events_completed = current_block->step_event_count; \
} \
old_## axis ##_## minmax ##_endstop = axis ##_## minmax ##_endstop;
_OLD_ENDSTOP(axis, minmax) = _ENDSTOP(axis, minmax);
// Check X and Y endstops
if (check_endstops) {
@ -469,7 +488,7 @@ ISR(TIMER1_COMPA_vect) {
if ((current_block->steps[A_AXIS] != current_block->steps[B_AXIS]) || (TEST(out_bits, A_AXIS) == TEST(out_bits, B_AXIS))) {
if (TEST(out_bits, X_HEAD))
#else
if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular cartesians bot)
if (TEST(out_bits, X_AXIS)) // stepping along -X axis (regular Cartesian bot)
#endif
{ // -direction
#ifdef DUAL_X_CARRIAGE
@ -656,6 +675,11 @@ ISR(TIMER1_COMPA_vect) {
}
#endif //ADVANCE
#define _COUNTER(axis) counter_## axis
#define _WRITE_STEP(AXIS, HIGHLOW) AXIS ##_STEP_WRITE(HIGHLOW)
#define _APPLY_STEP(AXIS) AXIS ##_APPLY_STEP
#define _INVERT_STEP_PIN(AXIS) INVERT_## AXIS ##_STEP_PIN
#ifdef CONFIG_STEPPERS_TOSHIBA
/**
* The Toshiba stepper controller require much longer pulses.
@ -664,8 +688,8 @@ ISR(TIMER1_COMPA_vect) {
* lag to allow it work with without needing NOPs
*/
#define STEP_ADD(axis, AXIS) \
counter_## axis += current_block->steps[AXIS ##_AXIS]; \
if (counter_## axis > 0) { AXIS ##_STEP_WRITE(HIGH); }
_COUNTER(axis) += current_block->steps[_AXIS(AXIS)]; \
if (_COUNTER(axis) > 0) { _WRITE_STEP(AXIS, HIGH); }
STEP_ADD(x,X);
STEP_ADD(y,Y);
STEP_ADD(z,Z);
@ -674,10 +698,10 @@ ISR(TIMER1_COMPA_vect) {
#endif
#define STEP_IF_COUNTER(axis, AXIS) \
if (counter_## axis > 0) { \
counter_## axis -= current_block->step_event_count; \
count_position[AXIS ##_AXIS] += count_direction[AXIS ##_AXIS]; \
AXIS ##_STEP_WRITE(LOW); \
if (_COUNTER(axis) > 0) { \
_COUNTER(axis) -= current_block->step_event_count; \
count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
_WRITE_STEP(AXIS, LOW); \
}
STEP_IF_COUNTER(x, X);
@ -690,12 +714,12 @@ ISR(TIMER1_COMPA_vect) {
#else // !CONFIG_STEPPERS_TOSHIBA
#define APPLY_MOVEMENT(axis, AXIS) \
counter_## axis += current_block->steps[AXIS ##_AXIS]; \
if (counter_## axis > 0) { \
AXIS ##_APPLY_STEP(!INVERT_## AXIS ##_STEP_PIN,0); \
counter_## axis -= current_block->step_event_count; \
count_position[AXIS ##_AXIS] += count_direction[AXIS ##_AXIS]; \
AXIS ##_APPLY_STEP(INVERT_## AXIS ##_STEP_PIN,0); \
_COUNTER(axis) += current_block->steps[_AXIS(AXIS)]; \
if (_COUNTER(axis) > 0) { \
_APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS),0); \
_COUNTER(axis) -= current_block->step_event_count; \
count_position[_AXIS(AXIS)] += count_direction[_AXIS(AXIS)]; \
_APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS),0); \
}
APPLY_MOVEMENT(x, X);
@ -714,7 +738,7 @@ ISR(TIMER1_COMPA_vect) {
unsigned short step_rate;
if (step_events_completed <= (unsigned long)current_block->accelerate_until) {
MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
MultiU24X32toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
acc_step_rate += current_block->initial_rate;
// upper limit
@ -737,7 +761,7 @@ ISR(TIMER1_COMPA_vect) {
#endif
}
else if (step_events_completed > (unsigned long)current_block->decelerate_after) {
MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
MultiU24X32toH16(step_rate, deceleration_time, current_block->acceleration_rate);
if (step_rate > acc_step_rate) { // Check step_rate stays positive
step_rate = current_block->final_rate;
@ -999,10 +1023,13 @@ void st_init() {
#endif
#endif
#define _STEP_INIT(AXIS) AXIS ##_STEP_INIT
#define _DISABLE(axis) disable_## axis()
#define AXIS_INIT(axis, AXIS, PIN) \
AXIS ##_STEP_INIT; \
AXIS ##_STEP_WRITE(INVERT_## PIN ##_STEP_PIN); \
disable_## axis()
_STEP_INIT(AXIS); \
_WRITE_STEP(AXIS, _INVERT_STEP_PIN(PIN)); \
_DISABLE(axis)
#define E_AXIS_INIT(NUM) AXIS_INIT(e## NUM, E## NUM, E)
@ -1135,14 +1162,19 @@ void quickStop() {
// No other ISR should ever interrupt this!
void babystep(const uint8_t axis, const bool direction) {
#define _ENABLE(axis) enable_## axis()
#define _READ_DIR(AXIS) AXIS ##_DIR_READ
#define _INVERT_DIR(AXIS) INVERT_## AXIS ##_DIR
#define _APPLY_DIR(AXIS, INVERT) AXIS ##_APPLY_DIR(INVERT, true)
#define BABYSTEP_AXIS(axis, AXIS, INVERT) { \
enable_## axis(); \
uint8_t old_pin = AXIS ##_DIR_READ; \
AXIS ##_APPLY_DIR(INVERT_## AXIS ##_DIR^direction^INVERT, true); \
AXIS ##_APPLY_STEP(!INVERT_## AXIS ##_STEP_PIN, true); \
_delay_us(1U); \
AXIS ##_APPLY_STEP(INVERT_## AXIS ##_STEP_PIN, true); \
AXIS ##_APPLY_DIR(old_pin, true); \
_ENABLE(axis); \
uint8_t old_pin = _READ_DIR(AXIS); \
_APPLY_DIR(AXIS, _INVERT_DIR(AXIS)^direction^INVERT); \
_APPLY_STEP(AXIS)(!_INVERT_STEP_PIN(AXIS), true); \
delayMicroseconds(2); \
_APPLY_STEP(AXIS)(_INVERT_STEP_PIN(AXIS), true); \
_APPLY_DIR(AXIS, old_pin); \
}
switch(axis) {
@ -1179,7 +1211,7 @@ void quickStop() {
X_STEP_WRITE(!INVERT_X_STEP_PIN);
Y_STEP_WRITE(!INVERT_Y_STEP_PIN);
Z_STEP_WRITE(!INVERT_Z_STEP_PIN);
_delay_us(1U);
delayMicroseconds(2);
X_STEP_WRITE(INVERT_X_STEP_PIN);
Y_STEP_WRITE(INVERT_Y_STEP_PIN);
Z_STEP_WRITE(INVERT_Z_STEP_PIN);

9
Marlin/temperature.cpp

@ -89,8 +89,9 @@ unsigned char soft_pwm_bed;
#endif
//===========================================================================
//=============================private variables============================
//============================ private variables ============================
//===========================================================================
static volatile bool temp_meas_ready = false;
#ifdef PIDTEMP
@ -187,7 +188,7 @@ static void updateTemperaturesFromRawValues();
#endif
//===========================================================================
//============================= functions ============================
//================================ Functions ================================
//===========================================================================
void PID_autotune(float temp, int extruder, int ncycles)
@ -341,6 +342,10 @@ void PID_autotune(float temp, int extruder, int ncycles)
}
if (cycles > ncycles) {
SERIAL_PROTOCOLLNPGM(MSG_PID_AUTOTUNE_FINISHED);
const char *estring = extruder < 0 ? "bed" : "";
SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Kp "); SERIAL_PROTOCOLLN(Kp);
SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Ki "); SERIAL_PROTOCOLLN(Ki);
SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Kd "); SERIAL_PROTOCOLLN(Kd);
return;
}
lcd_update();

366
Marlin/ultralcd.cpp

@ -5,7 +5,7 @@
#include "cardreader.h"
#include "temperature.h"
#include "stepper.h"
#include "ConfigurationStore.h"
#include "configuration_store.h"
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
@ -173,6 +173,9 @@ static void lcd_status_screen();
} while(0)
#ifdef ENCODER_RATE_MULTIPLIER
//#define ENCODER_RATE_MULTIPLIER_DEBUG // If defined, output the encoder steps per second value
/**
* MENU_MULTIPLIER_ITEM generates drawing and handling code for a multiplier menu item
*/
@ -246,6 +249,9 @@ menuFunc_t callbackFunc;
// place-holders for Ki and Kd edits
float raw_Ki, raw_Kd;
/**
* General function to go directly to a menu
*/
static void lcd_goto_menu(menuFunc_t menu, const bool feedback=false, const uint32_t encoder=0) {
if (currentMenu != menu) {
currentMenu = menu;
@ -260,35 +266,41 @@ static void lcd_goto_menu(menuFunc_t menu, const bool feedback=false, const uint
}
}
/* Main status screen. It's up to the implementation specific part to show what is needed. As this is very display dependent */
/**
*
* "Info Screen"
*
* This is very display-dependent, so the lcd implementation draws this.
*/
static void lcd_status_screen() {
encoderRateMultiplierEnabled = false;
#ifdef LCD_PROGRESS_BAR
millis_t ms = millis();
#ifndef PROGRESS_MSG_ONCE
if (ms > progressBarTick + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME) {
progressBarTick = ms;
if (ms > progress_bar_ms + PROGRESS_BAR_MSG_TIME + PROGRESS_BAR_BAR_TIME) {
progress_bar_ms = ms;
}
#endif
#if PROGRESS_MSG_EXPIRE > 0
// Handle message expire
if (expireStatusMillis > 0) {
if (expire_status_ms > 0) {
if (card.isFileOpen()) {
// Expire the message when printing is active
if (IS_SD_PRINTING) {
// Expire the message when printing is active
if (ms >= expireStatusMillis) {
if (ms >= expire_status_ms) {
lcd_status_message[0] = '\0';
expireStatusMillis = 0;
expire_status_ms = 0;
}
}
else {
expireStatusMillis += LCD_UPDATE_INTERVAL;
expire_status_ms += LCD_UPDATE_INTERVAL;
}
}
else {
expireStatusMillis = 0;
expire_status_ms = 0;
}
}
#endif
@ -371,7 +383,12 @@ static void lcd_sdcard_stop() {
lcd_setstatus(MSG_PRINT_ABORTED, true);
}
/* Menu implementation */
/**
*
* "Main" menu
*
*/
static void lcd_main_menu() {
START_MENU();
MENU_ITEM(back, MSG_WATCH, lcd_status_screen);
@ -421,17 +438,12 @@ static void lcd_main_menu() {
}
#endif
/**
* Set the home offset based on the current_position
*/
void lcd_set_home_offsets() {
for (int8_t i=0; i < NUM_AXIS; i++) {
if (i != E_AXIS) {
home_offset[i] -= current_position[i];
current_position[i] = 0.0;
}
}
plan_set_position(0.0, 0.0, 0.0, current_position[E_AXIS]);
// Audio feedback
enqueuecommands_P(PSTR("M300 S659 P200\nM300 S698 P200"));
// M428 Command
enqueuecommands_P(PSTR("M428"));
lcd_return_to_status();
}
@ -453,6 +465,12 @@ void lcd_set_home_offsets() {
#endif //BABYSTEPPING
/**
*
* "Tune" submenu
*
*/
static void lcd_tune_menu() {
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
@ -594,17 +612,55 @@ void lcd_cooldown() {
lcd_return_to_status();
}
/**
*
* "Prepare" submenu
*
*/
static void lcd_prepare_menu() {
START_MENU();
//
// ^ Main
//
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
#if defined( SDSUPPORT ) && defined( MENU_ADDAUTOSTART )
MENU_ITEM(function, MSG_AUTOSTART, lcd_autostart_sd);
#endif
MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84"));
//
// Auto Home
//
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
//
// Set Home Offsets
//
MENU_ITEM(function, MSG_SET_HOME_OFFSETS, lcd_set_home_offsets);
//MENU_ITEM(gcode, MSG_SET_ORIGIN, PSTR("G92 X0 Y0 Z0"));
//
// Level Bed
//
#ifdef ENABLE_AUTO_BED_LEVELING
if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS])
MENU_ITEM(gcode, MSG_LEVEL_BED, PSTR("G29"));
#elif defined(MANUAL_BED_LEVELING)
MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed);
#endif
//
// Move Axis
//
MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu);
//
// Disable Steppers
//
MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84"));
//
// Preheat PLA
// Preheat ABS
//
#if TEMP_SENSOR_0 != 0
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0
MENU_ITEM(submenu, MSG_PREHEAT_PLA, lcd_preheat_pla_menu);
@ -615,8 +671,14 @@ static void lcd_prepare_menu() {
#endif
#endif
//
// Cooldown
//
MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown);
//
// Switch power on/off
//
#if HAS_POWER_SWITCH
if (powersupply)
MENU_ITEM(gcode, MSG_SWITCH_PS_OFF, PSTR("M81"));
@ -624,10 +686,11 @@ static void lcd_prepare_menu() {
MENU_ITEM(gcode, MSG_SWITCH_PS_ON, PSTR("M80"));
#endif
MENU_ITEM(submenu, MSG_MOVE_AXIS, lcd_move_menu);
#if defined(MANUAL_BED_LEVELING)
MENU_ITEM(submenu, MSG_LEVEL_BED, lcd_level_bed);
//
// Autostart
//
#if defined(SDSUPPORT) && defined(MENU_ADDAUTOSTART)
MENU_ITEM(function, MSG_AUTOSTART, lcd_autostart_sd);
#endif
END_MENU();
@ -648,26 +711,32 @@ static void lcd_prepare_menu() {
#endif // DELTA_CALIBRATION_MENU
inline void line_to_current() {
inline void line_to_current(AxisEnum axis) {
#ifdef DELTA
calculate_delta(current_position);
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], manual_feedrate[X_AXIS]/60, active_extruder);
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS], manual_feedrate[axis]/60, active_extruder);
#else
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], manual_feedrate[X_AXIS]/60, active_extruder);
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], manual_feedrate[axis]/60, active_extruder);
#endif
}
/**
*
* "Prepare" > "Move Axis" submenu
*
*/
float move_menu_scale;
static void lcd_move_menu_axis();
static void _lcd_move(const char *name, int axis, int min, int max) {
static void _lcd_move(const char *name, AxisEnum axis, int min, int max) {
if (encoderPosition != 0) {
refresh_cmd_timeout();
current_position[axis] += float((int)encoderPosition) * move_menu_scale;
if (min_software_endstops && current_position[axis] < min) current_position[axis] = min;
if (max_software_endstops && current_position[axis] > max) current_position[axis] = max;
encoderPosition = 0;
line_to_current();
line_to_current(axis);
lcdDrawUpdate = 1;
}
if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr31(current_position[axis]));
@ -680,13 +749,19 @@ static void lcd_move_e() {
if (encoderPosition != 0) {
current_position[E_AXIS] += float((int)encoderPosition) * move_menu_scale;
encoderPosition = 0;
line_to_current();
line_to_current(E_AXIS);
lcdDrawUpdate = 1;
}
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR("Extruder"), ftostr31(current_position[E_AXIS]));
if (LCD_CLICKED) lcd_goto_menu(lcd_move_menu_axis);
}
/**
*
* "Prepare" > "Move Xmm" > "Move XYZ" submenu
*
*/
static void lcd_move_menu_axis() {
START_MENU();
MENU_ITEM(back, MSG_MOVE_AXIS, lcd_move_menu);
@ -712,6 +787,12 @@ static void lcd_move_menu_01mm() {
lcd_move_menu_axis();
}
/**
*
* "Prepare" > "Move Axis" submenu
*
*/
static void lcd_move_menu() {
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
@ -722,6 +803,12 @@ static void lcd_move_menu() {
END_MENU();
}
/**
*
* "Control" submenu
*
*/
static void lcd_control_menu() {
START_MENU();
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
@ -744,6 +831,12 @@ static void lcd_control_menu() {
END_MENU();
}
/**
*
* "Temperature" submenu
*
*/
#ifdef PIDTEMP
// Helpers for editing PID Ki & Kd values
@ -775,6 +868,12 @@ static void lcd_control_menu() {
#endif //PIDTEMP
/**
*
* "Control" > "Temperature" submenu
*
*/
static void lcd_control_temperature_menu() {
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
@ -863,15 +962,21 @@ static void lcd_control_temperature_menu() {
END_MENU();
}
/**
*
* "Temperature" > "Preheat PLA conf" submenu
*
*/
static void lcd_control_temperature_preheat_pla_settings_menu() {
START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &plaPreheatFanSpeed, 0, 255);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &plaPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &plaPreheatHotendTemp, HEATER_0_MINTEMP, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &plaPreheatHPBTemp, 0, BED_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_BED, &plaPreheatHPBTemp, BED_MINTEMP, BED_MAXTEMP - 15);
#endif
#ifdef EEPROM_SETTINGS
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
@ -879,15 +984,21 @@ static void lcd_control_temperature_preheat_pla_settings_menu() {
END_MENU();
}
/**
*
* "Temperature" > "Preheat ABS conf" submenu
*
*/
static void lcd_control_temperature_preheat_abs_settings_menu() {
START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE, lcd_control_temperature_menu);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &absPreheatFanSpeed, 0, 255);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &absPreheatHotendTemp, 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &absPreheatHotendTemp, HEATER_0_MINTEMP, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &absPreheatHPBTemp, 0, BED_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_BED, &absPreheatHPBTemp, BED_MINTEMP, BED_MAXTEMP - 15);
#endif
#ifdef EEPROM_SETTINGS
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
@ -895,6 +1006,12 @@ static void lcd_control_temperature_preheat_abs_settings_menu() {
END_MENU();
}
/**
*
* "Control" > "Motion" submenu
*
*/
static void lcd_control_motion_menu() {
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
@ -931,6 +1048,12 @@ static void lcd_control_motion_menu() {
END_MENU();
}
/**
*
* "Control" > "Filament" submenu
*
*/
static void lcd_control_volumetric_menu() {
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
@ -953,6 +1076,12 @@ static void lcd_control_volumetric_menu() {
END_MENU();
}
/**
*
* "Control" > "Contrast" submenu
*
*/
#ifdef HAS_LCD_CONTRAST
static void lcd_set_contrast() {
if (encoderPosition != 0) {
@ -967,6 +1096,12 @@ static void lcd_control_volumetric_menu() {
}
#endif // HAS_LCD_CONTRAST
/**
*
* "Control" > "Retract" submenu
*
*/
#ifdef FWRETRACT
static void lcd_control_retract_menu() {
START_MENU();
@ -999,6 +1134,12 @@ static void lcd_sd_updir() {
currentMenuViewOffset = 0;
}
/**
*
* "Print from SD" submenu
*
*/
void lcd_sdcard_menu() {
if (lcdDrawUpdate == 0 && LCD_CLICKED == 0) return; // nothing to do (so don't thrash the SD card)
uint16_t fileCnt = card.getnrfilenames();
@ -1034,6 +1175,11 @@ void lcd_sdcard_menu() {
END_MENU();
}
/**
*
* Functions for editing single values
*
*/
#define menu_edit_type(_type, _name, _strFunc, scale) \
bool _menu_edit_ ## _name () { \
bool isClicked = LCD_CLICKED; \
@ -1080,6 +1226,11 @@ menu_edit_type(float, float51, ftostr51, 10)
menu_edit_type(float, float52, ftostr52, 100)
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
/**
*
* Handlers for RepRap World Keypad input
*
*/
#ifdef REPRAPWORLD_KEYPAD
static void reprapworld_keypad_move_z_up() {
encoderPosition = 1;
@ -1116,8 +1267,12 @@ menu_edit_type(unsigned long, long5, ftostr5, 0.01)
}
#endif // REPRAPWORLD_KEYPAD
/** End of menus **/
/**
*
* Audio feedback for controller clicks
*
*/
void lcd_quick_feedback() {
lcdDrawUpdate = 2;
next_button_update_ms = millis() + 500;
@ -1130,32 +1285,31 @@ void lcd_quick_feedback() {
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS (1000/6)
#endif
lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ);
#elif defined(BEEPER) && BEEPER > -1
SET_OUTPUT(BEEPER);
#elif defined(BEEPER) && BEEPER >= 0
#ifndef LCD_FEEDBACK_FREQUENCY_HZ
#define LCD_FEEDBACK_FREQUENCY_HZ 5000
#endif
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
#endif
const uint16_t delay = 1000000 / LCD_FEEDBACK_FREQUENCY_HZ / 2;
uint16_t i = LCD_FEEDBACK_FREQUENCY_DURATION_MS * LCD_FEEDBACK_FREQUENCY_HZ / 1000;
while (i--) {
WRITE(BEEPER,HIGH);
delayMicroseconds(delay);
WRITE(BEEPER,LOW);
delayMicroseconds(delay);
}
const uint16_t j = max(10000 - LCD_FEEDBACK_FREQUENCY_DURATION_MS * 1000, 0);
if (j) delayMicroseconds(j);
lcd_buzz(LCD_FEEDBACK_FREQUENCY_DURATION_MS, LCD_FEEDBACK_FREQUENCY_HZ);
#else
#ifndef LCD_FEEDBACK_FREQUENCY_DURATION_MS
#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 2
#endif
delay(LCD_FEEDBACK_FREQUENCY_DURATION_MS);
#endif
}
/** Menu action functions **/
static void menu_action_back(menuFunc_t data) { lcd_goto_menu(data); }
static void menu_action_submenu(menuFunc_t data) { lcd_goto_menu(data); }
/**
*
* Menu actions
*
*/
static void menu_action_back(menuFunc_t func) { lcd_goto_menu(func); }
static void menu_action_submenu(menuFunc_t func) { lcd_goto_menu(func); }
static void menu_action_gcode(const char* pgcode) { enqueuecommands_P(pgcode); }
static void menu_action_function(menuFunc_t data) { (*data)(); }
static void menu_action_function(menuFunc_t func) { (*func)(); }
static void menu_action_sdfile(const char* filename, char* longFilename) {
char cmd[30];
char* c;
@ -1248,6 +1402,19 @@ int lcd_strlen_P(const char *s) {
return j;
}
/**
* Update the LCD, read encoder buttons, etc.
* - Read button states
* - Check the SD Card slot state
* - Act on RepRap World keypad input
* - Update the encoder position
* - Apply acceleration to the encoder position
* - Reset the Info Screen timeout if there's any input
* - Update status indicators, if any
* - Clear the LCD if lcdDrawUpdate == 2
*
* Warning: This function is called from interrupt context!
*/
void lcd_update() {
#ifdef ULTIPANEL
static millis_t return_to_status_ms = 0;
@ -1386,7 +1553,7 @@ void lcd_update() {
if (lcdDrawUpdate == 2) lcd_implementation_clear();
if (lcdDrawUpdate) lcdDrawUpdate--;
next_lcd_update_ms = millis() + LCD_UPDATE_INTERVAL;
next_lcd_update_ms = ms + LCD_UPDATE_INTERVAL;
}
}
@ -1397,9 +1564,9 @@ void lcd_ignore_click(bool b) {
void lcd_finishstatus(bool persist=false) {
#ifdef LCD_PROGRESS_BAR
progressBarTick = millis();
progress_bar_ms = millis();
#if PROGRESS_MSG_EXPIRE > 0
expireStatusMillis = persist ? 0 : progressBarTick + PROGRESS_MSG_EXPIRE;
expire_status_ms = persist ? 0 : progress_bar_ms + PROGRESS_MSG_EXPIRE;
#endif
#endif
lcdDrawUpdate = 2;
@ -1410,7 +1577,7 @@ void lcd_finishstatus(bool persist=false) {
}
#if defined(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0
void dontExpireStatus() { expireStatusMillis = 0; }
void dontExpireStatus() { expire_status_ms = 0; }
#endif
void set_utf_strlen(char *s, uint8_t n) {
@ -1423,6 +1590,8 @@ void set_utf_strlen(char *s, uint8_t n) {
s[i] = 0;
}
bool lcd_hasstatus() { return (lcd_status_message[0] != '\0'); }
void lcd_setstatus(const char* message, bool persist) {
if (lcd_status_message_level > 0) return;
strncpy(lcd_status_message, message, 3*LCD_WIDTH);
@ -1457,10 +1626,11 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; }
#ifdef ULTIPANEL
////////////////////////
// Setup Rotary Encoder Bit Values (for two pin encoders to indicate movement)
// These values are independent of which pins are used for EN_A and EN_B indications
// The rotary encoder part is also independent to the chipset used for the LCD
/**
* Setup Rotary Encoder Bit Values (for two pin encoders to indicate movement)
* These values are independent of which pins are used for EN_A and EN_B indications
* The rotary encoder part is also independent to the chipset used for the LCD
*/
#if defined(EN_A) && defined(EN_B)
#define encrot0 0
#define encrot1 2
@ -1468,7 +1638,10 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; }
#define encrot3 1
#endif
/* Warning: This function is called from interrupt context */
/**
* Read encoder buttons from the hardware registers
* Warning: This function is called from interrupt context!
*/
void lcd_buttons_update() {
#ifdef NEWPANEL
uint8_t newbutton = 0;
@ -1544,10 +1717,21 @@ bool lcd_detected(void) {
}
void lcd_buzz(long duration, uint16_t freq) {
if (freq > 0) {
#ifdef LCD_USE_I2C_BUZZER
lcd.buzz(duration, freq);
#elif defined(BEEPER) && BEEPER >= 0
SET_OUTPUT(BEEPER);
tone(BEEPER, freq, duration);
delay(duration);
#else
delay(duration);
#endif
}
else {
delay(duration);
}
}
bool lcd_clicked() { return LCD_CLICKED; }
@ -1613,8 +1797,7 @@ char *ftostr32(const float &x) {
}
// Convert float to string with 1.234 format
char *ftostr43(const float &x)
{
char *ftostr43(const float &x) {
long xx = x * 1000;
if (xx >= 0)
conv[0] = (xx / 1000) % 10 + '0';
@ -1630,8 +1813,7 @@ char *ftostr43(const float &x)
}
// Convert float to string with 1.23 format
char *ftostr12ns(const float &x)
{
char *ftostr12ns(const float &x) {
long xx=x*100;
xx=abs(xx);
@ -1791,6 +1973,12 @@ char *ftostr52(const float &x) {
#ifdef MANUAL_BED_LEVELING
static int _lcd_level_bed_position;
/**
* MBL Wait for controller movement and clicks:
* - Movement adjusts the Z axis
* - Click saves the Z and goes to the next mesh point
*/
static void _lcd_level_bed() {
if (encoderPosition != 0) {
refresh_cmd_timeout();
@ -1798,7 +1986,7 @@ char *ftostr52(const float &x) {
if (min_software_endstops && current_position[Z_AXIS] < Z_MIN_POS) current_position[Z_AXIS] = Z_MIN_POS;
if (max_software_endstops && current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
encoderPosition = 0;
line_to_current();
line_to_current(Z_AXIS);
lcdDrawUpdate = 2;
}
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR("Z"), ftostr43(current_position[Z_AXIS]));
@ -1806,58 +1994,58 @@ char *ftostr52(const float &x) {
if (LCD_CLICKED) {
if (!debounce_click) {
debounce_click = true;
int ix = _lcd_level_bed_position % MESH_NUM_X_POINTS;
int iy = _lcd_level_bed_position / MESH_NUM_X_POINTS;
if (iy&1) { // Zig zag
ix = (MESH_NUM_X_POINTS - 1) - ix;
}
int ix = _lcd_level_bed_position % MESH_NUM_X_POINTS,
iy = _lcd_level_bed_position / MESH_NUM_X_POINTS;
if (iy & 1) ix = (MESH_NUM_X_POINTS - 1) - ix; // Zig zag
mbl.set_z(ix, iy, current_position[Z_AXIS]);
_lcd_level_bed_position++;
if (_lcd_level_bed_position == MESH_NUM_X_POINTS*MESH_NUM_Y_POINTS) {
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
line_to_current();
line_to_current(Z_AXIS);
mbl.active = 1;
enqueuecommands_P(PSTR("G28"));
lcd_return_to_status();
} else {
}
else {
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
line_to_current();
line_to_current(Z_AXIS);
ix = _lcd_level_bed_position % MESH_NUM_X_POINTS;
iy = _lcd_level_bed_position / MESH_NUM_X_POINTS;
if (iy&1) { // Zig zag
ix = (MESH_NUM_X_POINTS - 1) - ix;
}
if (iy & 1) ix = (MESH_NUM_X_POINTS - 1) - ix; // Zig zag
current_position[X_AXIS] = mbl.get_x(ix);
current_position[Y_AXIS] = mbl.get_y(iy);
line_to_current();
line_to_current(manual_feedrate[X_AXIS] <= manual_feedrate[Y_AXIS] ? X_AXIS : Y_AXIS);
lcdDrawUpdate = 2;
}
}
} else {
}
else {
debounce_click = false;
}
}
/**
* MBL Move to mesh starting point
*/
static void _lcd_level_bed_homing() {
if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR("XYZ"), "Homing");
if (axis_known_position[X_AXIS] &&
axis_known_position[Y_AXIS] &&
axis_known_position[Z_AXIS]) {
if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS]) {
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
current_position[X_AXIS] = MESH_MIN_X;
current_position[Y_AXIS] = MESH_MIN_Y;
line_to_current();
line_to_current(manual_feedrate[X_AXIS] <= manual_feedrate[Y_AXIS] ? X_AXIS : Y_AXIS);
_lcd_level_bed_position = 0;
lcd_goto_menu(_lcd_level_bed);
}
lcdDrawUpdate = 2;
}
/**
* MBL entry-point
*/
static void lcd_level_bed() {
axis_known_position[X_AXIS] = false;
axis_known_position[Y_AXIS] = false;
axis_known_position[Z_AXIS] = false;
axis_known_position[X_AXIS] = axis_known_position[Y_AXIS] = axis_known_position[Z_AXIS] = false;
mbl.reset();
enqueuecommands_P(PSTR("G28"));
lcdDrawUpdate = 2;

6
Marlin/ultralcd.h

@ -8,6 +8,7 @@
int lcd_strlen_P(const char *s);
void lcd_update();
void lcd_init();
bool lcd_hasstatus();
void lcd_setstatus(const char* message, const bool persist=false);
void lcd_setstatuspgm(const char* message, const uint8_t level=0);
void lcd_setalertstatuspgm(const char* message);
@ -100,6 +101,7 @@
#else //no LCD
FORCE_INLINE void lcd_update() {}
FORCE_INLINE void lcd_init() {}
FORCE_INLINE bool lcd_hasstatus() { return false; }
FORCE_INLINE void lcd_setstatus(const char* message, const bool persist=false) {}
FORCE_INLINE void lcd_setstatuspgm(const char* message, const uint8_t level=0) {}
FORCE_INLINE void lcd_buttons_update() {}
@ -107,8 +109,8 @@
FORCE_INLINE void lcd_buzz(long duration, uint16_t freq) {}
FORCE_INLINE bool lcd_detected(void) { return true; }
#define LCD_MESSAGEPGM(x)
#define LCD_ALERTMESSAGEPGM(x)
#define LCD_MESSAGEPGM(x) do{}while(0)
#define LCD_ALERTMESSAGEPGM(x) do{}while(0)
#endif //ULTRA_LCD

9
Marlin/ultralcd_implementation_hitachi_HD44780.h

@ -194,9 +194,9 @@
#include "utf_mapper.h"
#ifdef LCD_PROGRESS_BAR
static uint16_t progressBarTick = 0;
static millis_t progress_bar_ms = 0;
#if PROGRESS_MSG_EXPIRE > 0
static uint16_t expireStatusMillis = 0;
static millis_t expire_status_ms = 0;
#endif
#define LCD_STR_PROGRESS "\x03\x04\x05"
#endif
@ -588,8 +588,9 @@ static void lcd_implementation_status_screen() {
#ifdef LCD_PROGRESS_BAR
if (card.isFileOpen()) {
if (millis() >= progressBarTick + PROGRESS_BAR_MSG_TIME || !lcd_status_message[0]) {
// draw the progress bar
// Draw the progress bar if the message has shown long enough
// or if there is no message set.
if (millis() >= progress_bar_ms + PROGRESS_BAR_MSG_TIME || !lcd_status_message[0]) {
int tix = (int)(card.percentDone() * LCD_WIDTH * 3) / 100,
cel = tix / 3, rem = tix % 3, i = LCD_WIDTH;
char msg[LCD_WIDTH+1], b = ' ';

14
Marlin/ultralcd_st7920_u8glib_rrd.h

@ -16,8 +16,8 @@
//#define PAGE_HEIGHT 16 //256 byte framebuffer
#define PAGE_HEIGHT 32 //512 byte framebuffer
#define WIDTH 128
#define HEIGHT 64
#define LCD_PIXEL_WIDTH 128
#define LCD_PIXEL_HEIGHT 64
#include <U8glib.h>
@ -64,12 +64,12 @@ uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, vo
ST7920_WRITE_BYTE(0x01); //clear CGRAM ram
u8g_Delay(15); //delay for CGRAM clear
ST7920_WRITE_BYTE(0x3E); //extended mode + GDRAM active
for(y=0;y<HEIGHT/2;y++) //clear GDRAM
for(y=0;y<LCD_PIXEL_HEIGHT/2;y++) //clear GDRAM
{
ST7920_WRITE_BYTE(0x80|y); //set y
ST7920_WRITE_BYTE(0x80); //set x = 0
ST7920_SET_DAT();
for(i=0;i<2*WIDTH/8;i++) //2x width clears both segments
for(i=0;i<2*LCD_PIXEL_WIDTH/8;i++) //2x width clears both segments
ST7920_WRITE_BYTE(0);
ST7920_SET_CMD();
}
@ -103,7 +103,7 @@ uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, vo
}
ST7920_SET_DAT();
ST7920_WRITE_BYTES(ptr,WIDTH/8); //ptr is incremented inside of macro
ST7920_WRITE_BYTES(ptr,LCD_PIXEL_WIDTH/8); //ptr is incremented inside of macro
y++;
}
ST7920_NCS();
@ -119,8 +119,8 @@ uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, vo
#endif
}
uint8_t u8g_dev_st7920_128x64_rrd_buf[WIDTH*(PAGE_HEIGHT/8)] U8G_NOCOMMON;
u8g_pb_t u8g_dev_st7920_128x64_rrd_pb = {{PAGE_HEIGHT,HEIGHT,0,0,0},WIDTH,u8g_dev_st7920_128x64_rrd_buf};
uint8_t u8g_dev_st7920_128x64_rrd_buf[LCD_PIXEL_WIDTH*(PAGE_HEIGHT/8)] U8G_NOCOMMON;
u8g_pb_t u8g_dev_st7920_128x64_rrd_pb = {{PAGE_HEIGHT,LCD_PIXEL_HEIGHT,0,0,0},LCD_PIXEL_WIDTH,u8g_dev_st7920_128x64_rrd_buf};
u8g_dev_t u8g_dev_st7920_128x64_rrd_sw_spi = {u8g_dev_rrd_st7920_128x64_fn,&u8g_dev_st7920_128x64_rrd_pb,&u8g_com_null_fn};
class U8GLIB_ST7920_128X64_RRD : public U8GLIB

6
Marlin/watchdog.cpp

@ -7,11 +7,11 @@
#include "ultralcd.h"
//===========================================================================
//=============================private variables ============================
//============================ private variables ============================
//===========================================================================
//===========================================================================
//=============================functinos ============================
//================================ functions ================================
//===========================================================================
@ -36,7 +36,7 @@ void watchdog_reset()
}
//===========================================================================
//=============================ISR ============================
//=================================== ISR ===================================
//===========================================================================
//Watchdog timer interrupt, called if main program blocks >1sec and manual reset is enabled.

2
README.md

@ -30,7 +30,7 @@ The Marlin development is currently revived. There's a long list of reported iss
## Contact
__Google Hangout:__ <a href="https://plus.google.com/hangouts/_/g2wp5duzb2y6ahikg6tmwao3kua" target="_blank">Hangout</a>
__Google Hangout:__ <a href="https://plus.google.com/hangouts/_/gxn3wrea5gdhoo223yimsiforia" target="_blank">Hangout</a>
## Credits

Loading…
Cancel
Save