Merge github.com:ErikZalm/Marlin into Marlin_v1
This commit is contained in:
commit
18199ff960
32 changed files with 2592 additions and 1559 deletions
|
@ -168,7 +168,7 @@ int main(void)
|
||||||
WDTCSR = 0;
|
WDTCSR = 0;
|
||||||
|
|
||||||
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
||||||
if (! (ch & _BV(EXTRF))) // if its a not an external reset...
|
if (! (ch & _BV(EXTRF))) // if it's a not an external reset...
|
||||||
app_start(); // skip bootloader
|
app_start(); // skip bootloader
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -168,7 +168,7 @@ int main(void)
|
||||||
WDTCSR = 0;
|
WDTCSR = 0;
|
||||||
|
|
||||||
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
||||||
if (! (ch & _BV(EXTRF))) // if its a not an external reset...
|
if (! (ch & _BV(EXTRF))) // if it's a not an external reset...
|
||||||
app_start(); // skip bootloader
|
app_start(); // skip bootloader
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
// S = 0; No shift
|
// S = 0; No shift
|
||||||
//
|
//
|
||||||
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
|
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
|
||||||
// can't assume that its in that state when a sketch starts (and the
|
// can't assume that it's in that state when a sketch starts (and the
|
||||||
// LiquidCrystal constructor is called).
|
// LiquidCrystal constructor is called).
|
||||||
|
|
||||||
LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t rw, uint8_t enable,
|
LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t rw, uint8_t enable,
|
||||||
|
|
|
@ -72,7 +72,7 @@
|
||||||
- Castling: Need to check for fields under attack
|
- Castling: Need to check for fields under attack
|
||||||
--> done
|
--> done
|
||||||
|
|
||||||
- Check for WIN / LOOSE situation, perhaps call ce_Eval() once on the top-level board setup
|
- Check for WIN / LOSE situation, perhaps call ce_Eval() once on the top-level board setup
|
||||||
just after the real move
|
just after the real move
|
||||||
- cleanup cu_Move
|
- cleanup cu_Move
|
||||||
--> almost done
|
--> almost done
|
||||||
|
|
|
@ -21,7 +21,7 @@
|
||||||
// S = 0; No shift
|
// S = 0; No shift
|
||||||
//
|
//
|
||||||
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
|
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
|
||||||
// can't assume that its in that state when a sketch starts (and the
|
// can't assume that it's in that state when a sketch starts (and the
|
||||||
// LiquidCrystal constructor is called).
|
// LiquidCrystal constructor is called).
|
||||||
|
|
||||||
LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t rw, uint8_t enable,
|
LiquidCrystal::LiquidCrystal(uint8_t rs, uint8_t rw, uint8_t enable,
|
||||||
|
|
|
@ -72,7 +72,7 @@
|
||||||
- Castling: Need to check for fields under attack
|
- Castling: Need to check for fields under attack
|
||||||
--> done
|
--> done
|
||||||
|
|
||||||
- Check for WIN / LOOSE situation, perhaps call ce_Eval() once on the top-level board setup
|
- Check for WIN / LOSE situation, perhaps call ce_Eval() once on the top-level board setup
|
||||||
just after the real move
|
just after the real move
|
||||||
- cleanup cu_Move
|
- cleanup cu_Move
|
||||||
--> almost done
|
--> almost done
|
||||||
|
|
|
@ -301,7 +301,7 @@ int main(void)
|
||||||
WDTCSR = 0;
|
WDTCSR = 0;
|
||||||
|
|
||||||
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
||||||
if (! (ch & _BV(EXTRF))) // if its a not an external reset...
|
if (! (ch & _BV(EXTRF))) // if it's a not an external reset...
|
||||||
app_start(); // skip bootloader
|
app_start(); // skip bootloader
|
||||||
#else
|
#else
|
||||||
asm volatile("nop\n\t");
|
asm volatile("nop\n\t");
|
||||||
|
|
|
@ -172,7 +172,7 @@ int main(void)
|
||||||
WDTCSR = 0;
|
WDTCSR = 0;
|
||||||
|
|
||||||
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
||||||
if (! (ch & _BV(EXTRF))) // if its a not an external reset...
|
if (! (ch & _BV(EXTRF))) // if it's a not an external reset...
|
||||||
app_start(); // skip bootloader
|
app_start(); // skip bootloader
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -172,7 +172,7 @@ int main(void)
|
||||||
WDTCSR = 0;
|
WDTCSR = 0;
|
||||||
|
|
||||||
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
// Check if the WDT was used to reset, in which case we dont bootload and skip straight to the code. woot.
|
||||||
if (! (ch & _BV(EXTRF))) // if its a not an external reset...
|
if (! (ch & _BV(EXTRF))) // if it's a not an external reset...
|
||||||
app_start(); // skip bootloader
|
app_start(); // skip bootloader
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -1,15 +1,15 @@
|
||||||
#ifndef CONFIGURATION_H
|
#ifndef CONFIGURATION_H
|
||||||
#define CONFIGURATION_H
|
#define CONFIGURATION_H
|
||||||
|
|
||||||
// This configurtion file contains the basic settings.
|
// This configuration file contains the basic settings.
|
||||||
// Advanced settings can be found in Configuration_adv.h
|
// Advanced settings can be found in Configuration_adv.h
|
||||||
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
// BASIC SETTINGS: select your board type, temperature sensor type, axis scaling, and endstop configuration
|
||||||
|
|
||||||
//User specified version info of this build to display in [Pronterface, etc] terminal window during startup.
|
// User-specified version info of this build to display in [Pronterface, etc] terminal window during
|
||||||
//Implementation of an idea by Prof Braino to inform user that any changes made
|
// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this
|
||||||
//to this build by the user have been successfully uploaded into firmware.
|
// build by the user have been successfully uploaded into firmware.
|
||||||
#define STRING_VERSION_CONFIG_H __DATE__ " " __TIME__ // build date and time
|
#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_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes.
|
||||||
|
|
||||||
// SERIAL_PORT selects which serial port should be used for communication with the host.
|
// 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.
|
// This allows the connection of wireless adapters (for instance) to non-default port pins.
|
||||||
|
@ -26,7 +26,7 @@
|
||||||
// 12 = Gen7 v1.3
|
// 12 = Gen7 v1.3
|
||||||
// 13 = Gen7 v1.4
|
// 13 = Gen7 v1.4
|
||||||
// 3 = MEGA/RAMPS up to 1.2 = 3
|
// 3 = MEGA/RAMPS up to 1.2 = 3
|
||||||
// 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Bed, Fan)
|
// 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Fan, Bed)
|
||||||
// 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
|
// 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed)
|
||||||
// 4 = Duemilanove w/ ATMega328P pin assignment
|
// 4 = Duemilanove w/ ATMega328P pin assignment
|
||||||
// 5 = Gen6
|
// 5 = Gen6
|
||||||
|
@ -35,8 +35,11 @@
|
||||||
// 62 = Sanguinololu 1.2 and above
|
// 62 = Sanguinololu 1.2 and above
|
||||||
// 63 = Melzi
|
// 63 = Melzi
|
||||||
// 64 = STB V1.1
|
// 64 = STB V1.1
|
||||||
|
// 65 = Azteeg X1
|
||||||
|
// 66 = Melzi with ATmega1284 (MaKr3d version)
|
||||||
// 7 = Ultimaker
|
// 7 = Ultimaker
|
||||||
// 71 = Ultimaker (Older electronics. Pre 1.5.4. This is rare)
|
// 71 = Ultimaker (Older electronics. Pre 1.5.4. This is rare)
|
||||||
|
// 77 = 3Drag Controller
|
||||||
// 8 = Teensylu
|
// 8 = Teensylu
|
||||||
// 80 = Rumba
|
// 80 = Rumba
|
||||||
// 81 = Printrboard (AT90USB1286)
|
// 81 = Printrboard (AT90USB1286)
|
||||||
|
@ -48,11 +51,15 @@
|
||||||
// 90 = Alpha OMCA board
|
// 90 = Alpha OMCA board
|
||||||
// 91 = Final OMCA board
|
// 91 = Final OMCA board
|
||||||
// 301 = Rambo
|
// 301 = Rambo
|
||||||
|
// 21 = Elefu Ra Board (v3)
|
||||||
|
|
||||||
#ifndef MOTHERBOARD
|
#ifndef MOTHERBOARD
|
||||||
#define MOTHERBOARD 7
|
#define MOTHERBOARD 7
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Define this to set a custom name for your generic Mendel,
|
||||||
|
// #define CUSTOM_MENDEL_NAME "This Mendel"
|
||||||
|
|
||||||
// This defines the number of extruders
|
// This defines the number of extruders
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
|
|
||||||
|
@ -62,6 +69,43 @@
|
||||||
|
|
||||||
#define POWER_SUPPLY 1
|
#define POWER_SUPPLY 1
|
||||||
|
|
||||||
|
|
||||||
|
//===========================================================================
|
||||||
|
//============================== Delta Settings =============================
|
||||||
|
//===========================================================================
|
||||||
|
// Enable DELTA kinematics
|
||||||
|
//#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 200
|
||||||
|
|
||||||
|
// Center-to-center distance of the holes in the diagonal push rods.
|
||||||
|
#define DELTA_DIAGONAL_ROD 250.0 // mm
|
||||||
|
|
||||||
|
// Horizontal offset from middle of printer to smooth rod center.
|
||||||
|
#define DELTA_SMOOTH_ROD_OFFSET 175.0 // mm
|
||||||
|
|
||||||
|
// Horizontal offset of the universal joints on the end effector.
|
||||||
|
#define DELTA_EFFECTOR_OFFSET 33.0 // mm
|
||||||
|
|
||||||
|
// Horizontal offset of the universal joints on the carriages.
|
||||||
|
#define DELTA_CARRIAGE_OFFSET 18.0 // mm
|
||||||
|
|
||||||
|
// Effective horizontal distance bridged by diagonal push rods.
|
||||||
|
#define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET-DELTA_EFFECTOR_OFFSET-DELTA_CARRIAGE_OFFSET)
|
||||||
|
|
||||||
|
// Effective X/Y positions of the three vertical towers.
|
||||||
|
#define SIN_60 0.8660254037844386
|
||||||
|
#define COS_60 0.5
|
||||||
|
#define DELTA_TOWER1_X -SIN_60*DELTA_RADIUS // front left tower
|
||||||
|
#define DELTA_TOWER1_Y -COS_60*DELTA_RADIUS
|
||||||
|
#define DELTA_TOWER2_X SIN_60*DELTA_RADIUS // front right tower
|
||||||
|
#define DELTA_TOWER2_Y -COS_60*DELTA_RADIUS
|
||||||
|
#define DELTA_TOWER3_X 0.0 // back middle tower
|
||||||
|
#define DELTA_TOWER3_Y DELTA_RADIUS
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================Thermal Settings ============================
|
//=============================Thermal Settings ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -82,6 +126,7 @@
|
||||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (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)
|
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
||||||
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
||||||
|
// 60 is 100k Maker's Tool Works Kapton Bed Thermister
|
||||||
//
|
//
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
// 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)
|
// (but gives greater accuracy and more stable PID)
|
||||||
|
@ -90,14 +135,18 @@
|
||||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan) (1k pullup)
|
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan) (1k pullup)
|
||||||
|
|
||||||
#define TEMP_SENSOR_0 -1
|
#define TEMP_SENSOR_0 -1
|
||||||
#define TEMP_SENSOR_1 0
|
#define TEMP_SENSOR_1 -1
|
||||||
#define TEMP_SENSOR_2 0
|
#define TEMP_SENSOR_2 0
|
||||||
#define TEMP_SENSOR_BED 0
|
#define TEMP_SENSOR_BED 0
|
||||||
|
|
||||||
|
// 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
|
// Actual temperature must be close to target for this long before M109 returns success
|
||||||
#define TEMP_RESIDENCY_TIME 10 // (seconds)
|
#define TEMP_RESIDENCY_TIME 10 // (seconds)
|
||||||
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
|
#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 recidency timer x degC early.
|
#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
|
// 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.
|
// to check that the wiring to the thermistor is not broken.
|
||||||
|
@ -123,15 +172,15 @@
|
||||||
// PID settings:
|
// PID settings:
|
||||||
// Comment the following line to disable PID and enable bang-bang.
|
// Comment the following line to disable PID and enable bang-bang.
|
||||||
#define PIDTEMP
|
#define PIDTEMP
|
||||||
#define BANG_MAX 256 // limits current to nozzle while in bang-bang mode; 256=full current
|
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
|
||||||
#define PID_MAX 256 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 256=full current
|
#define PID_MAX 255 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
//#define PID_DEBUG // Sends debug data to the serial port.
|
//#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 PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
|
||||||
#define PID_FUNCTIONAL_RANGE 10 // If the temperature difference between the target temperature and the actual temperature
|
#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.
|
// 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 255 //limit for the integral term
|
#define PID_INTEGRAL_DRIVE_MAX 255 //limit for the integral term
|
||||||
#define K1 0.95 //smoothing factor withing the PID
|
#define K1 0.95 //smoothing factor within the PID
|
||||||
#define PID_dT ((16.0 * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
|
#define PID_dT ((16.0 * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine
|
||||||
|
|
||||||
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
|
// If you are using a preconfigured hotend then you can use one of the value sets by uncommenting it
|
||||||
|
@ -152,28 +201,28 @@
|
||||||
#endif // PIDTEMP
|
#endif // PIDTEMP
|
||||||
|
|
||||||
// Bed Temperature Control
|
// Bed Temperature Control
|
||||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
// 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.
|
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
||||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
// If your PID_dT above 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.
|
// 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.
|
// 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 proabaly
|
// 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.
|
// shouldn't use bed PID until someone else verifies your hardware works.
|
||||||
// If this is enabled, find your own PID constants below.
|
// If this is enabled, find your own PID constants below.
|
||||||
//#define PIDTEMPBED
|
//#define PIDTEMPBED
|
||||||
//
|
//
|
||||||
//#define BED_LIMIT_SWITCHING
|
//#define BED_LIMIT_SWITCHING
|
||||||
|
|
||||||
// This sets the max power delived to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
// 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)
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
// setting this to anything other than 256 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
// 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)
|
// 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 256 // limits duty cycle to bed; 256=full current
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
#ifdef PIDTEMPBED
|
#ifdef PIDTEMPBED
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, argressive factor of .15 (vs .1, 1, 10)
|
//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_bedKp 10.00
|
||||||
#define DEFAULT_bedKi .023
|
#define DEFAULT_bedKi .023
|
||||||
#define DEFAULT_bedKd 305.4
|
#define DEFAULT_bedKd 305.4
|
||||||
|
@ -205,17 +254,17 @@
|
||||||
// Uncomment the following line to enable CoreXY kinematics
|
// Uncomment the following line to enable CoreXY kinematics
|
||||||
// #define COREXY
|
// #define COREXY
|
||||||
|
|
||||||
// corse Endstop Settings
|
// coarse Endstop Settings
|
||||||
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
|
||||||
|
|
||||||
#ifndef ENDSTOPPULLUPS
|
#ifndef ENDSTOPPULLUPS
|
||||||
// fine Enstop settings: Individual Pullups. will be ignord if ENDSTOPPULLUPS is defined
|
// fine Enstop settings: Individual Pullups. will be ignored if ENDSTOPPULLUPS is defined
|
||||||
#define ENDSTOPPULLUP_XMAX
|
// #define ENDSTOPPULLUP_XMAX
|
||||||
#define ENDSTOPPULLUP_YMAX
|
// #define ENDSTOPPULLUP_YMAX
|
||||||
#define ENDSTOPPULLUP_ZMAX
|
// #define ENDSTOPPULLUP_ZMAX
|
||||||
#define ENDSTOPPULLUP_XMIN
|
// #define ENDSTOPPULLUP_XMIN
|
||||||
#define ENDSTOPPULLUP_YMIN
|
// #define ENDSTOPPULLUP_YMIN
|
||||||
//#define ENDSTOPPULLUP_ZMIN
|
// #define ENDSTOPPULLUP_ZMIN
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef ENDSTOPPULLUPS
|
#ifdef ENDSTOPPULLUPS
|
||||||
|
@ -232,6 +281,12 @@ const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
||||||
const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops.
|
||||||
//#define DISABLE_MAX_ENDSTOPS
|
//#define DISABLE_MAX_ENDSTOPS
|
||||||
|
//#define DISABLE_MIN_ENDSTOPS
|
||||||
|
|
||||||
|
// Disable max endstops for compatibility with endstop checking routine
|
||||||
|
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
|
||||||
|
#define DISABLE_MAX_ENDSTOPS
|
||||||
|
#endif
|
||||||
|
|
||||||
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
|
||||||
#define X_ENABLE_ON 0
|
#define X_ENABLE_ON 0
|
||||||
|
@ -258,8 +313,8 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
#define Y_HOME_DIR -1
|
#define Y_HOME_DIR -1
|
||||||
#define Z_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 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.
|
#define max_software_endstops true // If true, axis won't move to coordinates greater than the defined lengths below.
|
||||||
// Travel limits after homing
|
// Travel limits after homing
|
||||||
#define X_MAX_POS 205
|
#define X_MAX_POS 205
|
||||||
#define X_MIN_POS 0
|
#define X_MIN_POS 0
|
||||||
|
@ -277,9 +332,11 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
//#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
|
//#define BED_CENTER_AT_0_0 // If defined, the center of the bed is at (X=0, Y=0)
|
||||||
|
|
||||||
//Manual homing switch locations:
|
//Manual homing switch locations:
|
||||||
|
// For deltabots this means top and center of the cartesian print volume.
|
||||||
#define MANUAL_X_HOME_POS 0
|
#define MANUAL_X_HOME_POS 0
|
||||||
#define MANUAL_Y_HOME_POS 0
|
#define MANUAL_Y_HOME_POS 0
|
||||||
#define MANUAL_Z_HOME_POS 0
|
#define MANUAL_Z_HOME_POS 0
|
||||||
|
//#define MANUAL_Z_HOME_POS 402 // For delta: Distance between nozzle and print surface after homing.
|
||||||
|
|
||||||
//// MOVEMENT SETTINGS
|
//// MOVEMENT SETTINGS
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
|
@ -287,12 +344,12 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
|
|
||||||
// default settings
|
// default settings
|
||||||
|
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for ultimaker
|
#define DEFAULT_AXIS_STEPS_PER_UNIT {78.7402,78.7402,200.0*8/3,760*1.1} // default steps per unit for Ultimaker
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
#define DEFAULT_MAX_FEEDRATE {500, 500, 5, 25} // (mm/sec)
|
||||||
#define DEFAULT_MAX_ACCELERATION {9000,9000,100,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_MAX_ACCELERATION {9000,9000,100,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 max acceleration in mm/s^2 for printing moves
|
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
|
||||||
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for r retracts
|
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
||||||
|
|
||||||
// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing).
|
// 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).
|
// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder).
|
||||||
|
@ -300,7 +357,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
// #define EXTRUDER_OFFSET_X {0.0, 20.00} // (in mm) for each extruder, offset of the hotend on the X axis
|
// #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
|
// #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 instanteneously)
|
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
|
||||||
#define DEFAULT_XYJERK 20.0 // (mm/sec)
|
#define DEFAULT_XYJERK 20.0 // (mm/sec)
|
||||||
#define DEFAULT_ZJERK 0.4 // (mm/sec)
|
#define DEFAULT_ZJERK 0.4 // (mm/sec)
|
||||||
#define DEFAULT_EJERK 5.0 // (mm/sec)
|
#define DEFAULT_EJERK 5.0 // (mm/sec)
|
||||||
|
@ -338,6 +395,10 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
//#define ULTIMAKERCONTROLLER //as available from the ultimaker online store.
|
//#define ULTIMAKERCONTROLLER //as available from the ultimaker online store.
|
||||||
//#define ULTIPANEL //the ultipanel as on thingiverse
|
//#define ULTIPANEL //the ultipanel as on thingiverse
|
||||||
|
|
||||||
|
// The MaKr3d Makr-Panel with graphic controller and SD support
|
||||||
|
// http://reprap.org/wiki/MaKr3d_MaKrPanel
|
||||||
|
//#define MAKRPANEL
|
||||||
|
|
||||||
// The RepRapDiscount Smart Controller (white PCB)
|
// The RepRapDiscount Smart Controller (white PCB)
|
||||||
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
|
// http://reprap.org/wiki/RepRapDiscount_Smart_Controller
|
||||||
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
//#define REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
|
@ -357,7 +418,20 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
//#define REPRAPWORLD_KEYPAD
|
//#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
|
//#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 ARUDINO library folder: https://github.com/kiyoshigawa/LiquidCrystal_I2C
|
||||||
|
//#define RA_CONTROL_PANEL
|
||||||
|
|
||||||
//automatic expansion
|
//automatic expansion
|
||||||
|
#if defined (MAKRPANEL)
|
||||||
|
#define DOGLCD
|
||||||
|
#define SDSUPPORT
|
||||||
|
#define ULTIPANEL
|
||||||
|
#define NEWPANEL
|
||||||
|
#define DEFAULT_LCD_CONTRAST 17
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
|
#if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER)
|
||||||
#define DOGLCD
|
#define DOGLCD
|
||||||
#define U8GLIB_ST7920
|
#define U8GLIB_ST7920
|
||||||
|
@ -373,6 +447,12 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
#define NEWPANEL
|
#define NEWPANEL
|
||||||
#define ULTIPANEL
|
#define ULTIPANEL
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(RA_CONTROL_PANEL)
|
||||||
|
#define ULTIPANEL
|
||||||
|
#define NEWPANEL
|
||||||
|
#define LCD_I2C_TYPE_PCA8574
|
||||||
|
#define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander
|
||||||
|
#endif
|
||||||
|
|
||||||
//I2C PANELS
|
//I2C PANELS
|
||||||
|
|
||||||
|
@ -438,9 +518,27 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// default LCD contrast for dogm-like LCD displays
|
||||||
|
#ifdef DOGLCD
|
||||||
|
# ifndef DEFAULT_LCD_CONTRAST
|
||||||
|
# define DEFAULT_LCD_CONTRAST 32
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
|
||||||
//#define FAST_PWM_FAN
|
//#define FAST_PWM_FAN
|
||||||
|
|
||||||
|
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
|
||||||
|
// which is not ass 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
|
||||||
|
|
||||||
// M240 Triggers a camera by emulating a Canon RC-1 Remote
|
// M240 Triggers a camera by emulating a Canon RC-1 Remote
|
||||||
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/
|
||||||
// #define PHOTOGRAPH_PIN 23
|
// #define PHOTOGRAPH_PIN 23
|
||||||
|
@ -452,11 +550,8 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
//#define BARICUDA
|
//#define BARICUDA
|
||||||
|
|
||||||
/*********************************************************************\
|
/*********************************************************************\
|
||||||
*
|
|
||||||
* R/C SERVO support
|
* R/C SERVO support
|
||||||
*
|
|
||||||
* Sponsored by TrinityLabs, Reworked by codexmas
|
* Sponsored by TrinityLabs, Reworked by codexmas
|
||||||
*
|
|
||||||
**********************************************************************/
|
**********************************************************************/
|
||||||
|
|
||||||
// Number of servos
|
// Number of servos
|
||||||
|
@ -466,7 +561,15 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
|
||||||
// leaving it undefined or defining as 0 will disable the servo subsystem
|
// leaving it undefined or defining as 0 will disable the servo subsystem
|
||||||
// If unsure, leave commented / disabled
|
// If unsure, leave commented / disabled
|
||||||
//
|
//
|
||||||
// #define NUM_SERVOS 3
|
//#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 M206 command to correct for switch height offset to actual nozzle height. 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
|
||||||
|
|
||||||
#include "Configuration_adv.h"
|
#include "Configuration_adv.h"
|
||||||
#include "thermistortables.h"
|
#include "thermistortables.h"
|
||||||
|
|
|
@ -37,7 +37,7 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size)
|
||||||
// the default values are used whenever there is a change to the data, to prevent
|
// the default values are used whenever there is a change to the data, to prevent
|
||||||
// wrong data being written to the variables.
|
// wrong data being written to the variables.
|
||||||
// ALSO: always make sure the variables in the Store and retrieve sections are in the same order.
|
// ALSO: always make sure the variables in the Store and retrieve sections are in the same order.
|
||||||
#define EEPROM_VERSION "V07"
|
#define EEPROM_VERSION "V08"
|
||||||
|
|
||||||
#ifdef EEPROM_SETTINGS
|
#ifdef EEPROM_SETTINGS
|
||||||
void Config_StoreSettings()
|
void Config_StoreSettings()
|
||||||
|
@ -78,6 +78,10 @@ void Config_StoreSettings()
|
||||||
EEPROM_WRITE_VAR(i,dummy);
|
EEPROM_WRITE_VAR(i,dummy);
|
||||||
EEPROM_WRITE_VAR(i,dummy);
|
EEPROM_WRITE_VAR(i,dummy);
|
||||||
#endif
|
#endif
|
||||||
|
#ifndef DOGLCD
|
||||||
|
int lcd_contrast = 32;
|
||||||
|
#endif
|
||||||
|
EEPROM_WRITE_VAR(i,lcd_contrast);
|
||||||
char ver2[4]=EEPROM_VERSION;
|
char ver2[4]=EEPROM_VERSION;
|
||||||
i=EEPROM_OFFSET;
|
i=EEPROM_OFFSET;
|
||||||
EEPROM_WRITE_VAR(i,ver2); // validate data
|
EEPROM_WRITE_VAR(i,ver2); // validate data
|
||||||
|
@ -198,6 +202,10 @@ void Config_RetrieveSettings()
|
||||||
EEPROM_READ_VAR(i,Kp);
|
EEPROM_READ_VAR(i,Kp);
|
||||||
EEPROM_READ_VAR(i,Ki);
|
EEPROM_READ_VAR(i,Ki);
|
||||||
EEPROM_READ_VAR(i,Kd);
|
EEPROM_READ_VAR(i,Kd);
|
||||||
|
#ifndef DOGLCD
|
||||||
|
int lcd_contrast;
|
||||||
|
#endif
|
||||||
|
EEPROM_READ_VAR(i,lcd_contrast);
|
||||||
|
|
||||||
// Call updatePID (similar to when we have processed M301)
|
// Call updatePID (similar to when we have processed M301)
|
||||||
updatePID();
|
updatePID();
|
||||||
|
@ -244,6 +252,9 @@ void Config_ResetDefault()
|
||||||
absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP;
|
absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP;
|
||||||
absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED;
|
absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef DOGLCD
|
||||||
|
lcd_contrast = DEFAULT_LCD_CONTRAST;
|
||||||
|
#endif
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
Kp = DEFAULT_Kp;
|
Kp = DEFAULT_Kp;
|
||||||
Ki = scalePID_i(DEFAULT_Ki);
|
Ki = scalePID_i(DEFAULT_Ki);
|
||||||
|
|
|
@ -18,12 +18,6 @@
|
||||||
//#define WATCH_TEMP_PERIOD 40000 //40 seconds
|
//#define WATCH_TEMP_PERIOD 40000 //40 seconds
|
||||||
//#define WATCH_TEMP_INCREASE 10 //Heat up at least 10 degree in 20 seconds
|
//#define WATCH_TEMP_INCREASE 10 //Heat up at least 10 degree in 20 seconds
|
||||||
|
|
||||||
// Wait for Cooldown
|
|
||||||
// This defines if the M109 call should not block if it is cooling down.
|
|
||||||
// example: From a current temp of 220, you set M109 S200.
|
|
||||||
// if CooldownNoWait is defined M109 will not wait for the cooldown to finish
|
|
||||||
#define CooldownNoWait true
|
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
// this adds an experimental additional term to the heatingpower, proportional to the extrusion speed.
|
// this adds an experimental additional term to the heatingpower, proportional to the extrusion speed.
|
||||||
// if Kc is choosen well, the additional required power due to increased melting should be compensated.
|
// if Kc is choosen well, the additional required power due to increased melting should be compensated.
|
||||||
|
@ -152,6 +146,31 @@
|
||||||
#define EXTRUDERS 1
|
#define EXTRUDERS 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Enable this for dual x-carriage printers.
|
||||||
|
// A dual x-carriage design has the advantage that the inactive extruder can be parked which
|
||||||
|
// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage
|
||||||
|
// allowing faster printing speeds.
|
||||||
|
//#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 88 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage
|
||||||
|
#define X2_MAX_POS 350.45 // 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
|
||||||
|
|
||||||
|
#endif // DUAL_X_CARRIAGE
|
||||||
|
|
||||||
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
|
||||||
#define X_HOME_RETRACT_MM 5
|
#define X_HOME_RETRACT_MM 5
|
||||||
#define Y_HOME_RETRACT_MM 5
|
#define Y_HOME_RETRACT_MM 5
|
||||||
|
@ -318,6 +337,9 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= Define Defines ============================
|
//============================= Define Defines ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
#if EXTRUDERS > 1 && defined TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
#error "You cannot use TEMP_SENSOR_1_AS_REDUNDANT if EXTRUDERS > 1"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if TEMP_SENSOR_0 > 0
|
#if TEMP_SENSOR_0 > 0
|
||||||
#define THERMISTORHEATER_0 TEMP_SENSOR_0
|
#define THERMISTORHEATER_0 TEMP_SENSOR_0
|
||||||
|
|
|
@ -36,7 +36,7 @@ const PROGMEM uint8_t utf_recode[] =
|
||||||
// S = 0; No shift
|
// S = 0; No shift
|
||||||
//
|
//
|
||||||
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
|
// Note, however, that resetting the Arduino doesn't reset the LCD, so we
|
||||||
// can't assume that its in that state when a sketch starts (and the
|
// can't assume that it's in that state when a sketch starts (and the
|
||||||
// LiquidCrystal constructor is called).
|
// LiquidCrystal constructor is called).
|
||||||
//
|
//
|
||||||
// modified 27 Jul 2011
|
// modified 27 Jul 2011
|
||||||
|
|
|
@ -114,6 +114,12 @@ MCU ?= atmega644p
|
||||||
else ifeq ($(HARDWARE_MOTHERBOARD),63)
|
else ifeq ($(HARDWARE_MOTHERBOARD),63)
|
||||||
HARDWARE_VARIANT ?= Sanguino
|
HARDWARE_VARIANT ?= Sanguino
|
||||||
MCU ?= atmega644p
|
MCU ?= atmega644p
|
||||||
|
else ifeq ($(HARDWARE_MOTHERBOARD),65)
|
||||||
|
HARDWARE_VARIANT ?= Sanguino
|
||||||
|
MCU ?= atmega1284p
|
||||||
|
else ifeq ($(HARDWARE_MOTHERBOARD),66)
|
||||||
|
HARDWARE_VARIANT ?= Sanguino
|
||||||
|
MCU ?= atmega1284p
|
||||||
|
|
||||||
#Ultimaker
|
#Ultimaker
|
||||||
else ifeq ($(HARDWARE_MOTHERBOARD),7)
|
else ifeq ($(HARDWARE_MOTHERBOARD),7)
|
||||||
|
@ -213,7 +219,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
|
||||||
SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp \
|
SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp \
|
||||||
stepper.cpp temperature.cpp cardreader.cpp ConfigurationStore.cpp \
|
stepper.cpp temperature.cpp cardreader.cpp ConfigurationStore.cpp \
|
||||||
watchdog.cpp
|
watchdog.cpp
|
||||||
CXXSRC += LiquidCrystal.cpp ultralcd.cpp SPI.cpp Servo.cpp
|
CXXSRC += LiquidCrystal.cpp ultralcd.cpp SPI.cpp Servo.cpp Tone.cpp
|
||||||
|
|
||||||
#Check for Arduino 1.0.0 or higher and use the correct sourcefiles for that version
|
#Check for Arduino 1.0.0 or higher and use the correct sourcefiles for that version
|
||||||
ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
|
ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true)
|
||||||
|
@ -287,7 +293,7 @@ LDFLAGS = -lm
|
||||||
# Programming support using avrdude. Settings and variables.
|
# Programming support using avrdude. Settings and variables.
|
||||||
AVRDUDE_PORT = $(UPLOAD_PORT)
|
AVRDUDE_PORT = $(UPLOAD_PORT)
|
||||||
AVRDUDE_WRITE_FLASH = -U flash:w:$(BUILD_DIR)/$(TARGET).hex:i
|
AVRDUDE_WRITE_FLASH = -U flash:w:$(BUILD_DIR)/$(TARGET).hex:i
|
||||||
AVRDUDE_FLAGS = -D -C $(ARDUINO_INSTALL_DIR)/hardware/tools/avrdude.conf \
|
AVRDUDE_FLAGS = -D -C $(ARDUINO_INSTALL_DIR)/hardware/tools/avr/etc/avrdude.conf \
|
||||||
-p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \
|
-p $(MCU) -P $(AVRDUDE_PORT) -c $(AVRDUDE_PROGRAMMER) \
|
||||||
-b $(UPLOAD_RATE)
|
-b $(UPLOAD_RATE)
|
||||||
|
|
||||||
|
|
|
@ -96,7 +96,11 @@ void process_commands();
|
||||||
|
|
||||||
void manage_inactivity();
|
void manage_inactivity();
|
||||||
|
|
||||||
#if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
|
#if defined(DUAL_X_CARRIAGE) && defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1 \
|
||||||
|
&& defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
|
||||||
|
#define enable_x() do { WRITE(X_ENABLE_PIN, X_ENABLE_ON); WRITE(X2_ENABLE_PIN, X_ENABLE_ON); } while (0)
|
||||||
|
#define disable_x() do { WRITE(X_ENABLE_PIN,!X_ENABLE_ON); WRITE(X2_ENABLE_PIN,!X_ENABLE_ON); } while (0)
|
||||||
|
#elif defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
|
||||||
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
#define enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
|
||||||
#define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
|
#define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
|
||||||
#else
|
#else
|
||||||
|
@ -157,6 +161,9 @@ void FlushSerialRequestResend();
|
||||||
void ClearToSend();
|
void ClearToSend();
|
||||||
|
|
||||||
void get_coordinates();
|
void get_coordinates();
|
||||||
|
#ifdef DELTA
|
||||||
|
void calculate_delta(float cartesian[3]);
|
||||||
|
#endif
|
||||||
void prepare_move();
|
void prepare_move();
|
||||||
void kill();
|
void kill();
|
||||||
void Stop();
|
void Stop();
|
||||||
|
@ -191,6 +198,10 @@ extern int ValvePressure;
|
||||||
extern int EtoPPressure;
|
extern int EtoPPressure;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef FAN_SOFT_PWM
|
||||||
|
extern unsigned char fanSpeedSoftPwm;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef FWRETRACT
|
#ifdef FWRETRACT
|
||||||
extern bool autoretract_enabled;
|
extern bool autoretract_enabled;
|
||||||
extern bool retracted;
|
extern bool retracted;
|
||||||
|
|
|
@ -67,17 +67,9 @@
|
||||||
// G91 - Use Relative Coordinates
|
// G91 - Use Relative Coordinates
|
||||||
// G92 - Set current position to cordinates given
|
// G92 - Set current position to cordinates given
|
||||||
|
|
||||||
//RepRap M Codes
|
// M Codes
|
||||||
// M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
|
// M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
|
||||||
// M1 - Same as M0
|
// M1 - Same as M0
|
||||||
// M104 - Set extruder target temp
|
|
||||||
// M105 - Read current temp
|
|
||||||
// M106 - Fan on
|
|
||||||
// M107 - Fan off
|
|
||||||
// M109 - Wait for extruder current temp to reach target temp.
|
|
||||||
// M114 - Display current position
|
|
||||||
|
|
||||||
//Custom M Codes
|
|
||||||
// M17 - Enable/Power all stepper motors
|
// M17 - Enable/Power all stepper motors
|
||||||
// M18 - Disable all stepper motors; same as M84
|
// M18 - Disable all stepper motors; same as M84
|
||||||
// M20 - List SD card
|
// M20 - List SD card
|
||||||
|
@ -92,6 +84,7 @@
|
||||||
// M29 - Stop SD write
|
// M29 - Stop SD write
|
||||||
// M30 - Delete file from SD (M30 filename.g)
|
// M30 - Delete file from SD (M30 filename.g)
|
||||||
// M31 - Output time since last M109 or SD card start to serial
|
// M31 - Output time since last M109 or SD card start to serial
|
||||||
|
// M32 - Select file and start SD print (Can be used when printing from SD card)
|
||||||
// M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
|
// M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
|
||||||
// M80 - Turn on Power Supply
|
// M80 - Turn on Power Supply
|
||||||
// M81 - Turn off Power Supply
|
// M81 - Turn off Power Supply
|
||||||
|
@ -101,6 +94,12 @@
|
||||||
// or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
|
// or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
|
||||||
// M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
// M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
||||||
// M92 - Set axis_steps_per_unit - same syntax as G92
|
// M92 - Set axis_steps_per_unit - same syntax as G92
|
||||||
|
// M104 - Set extruder target temp
|
||||||
|
// M105 - Read current temp
|
||||||
|
// M106 - Fan on
|
||||||
|
// M107 - Fan off
|
||||||
|
// M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
|
||||||
|
// Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
|
||||||
// M114 - Output current position to serial port
|
// M114 - Output current position to serial port
|
||||||
// M115 - Capabilities string
|
// M115 - Capabilities string
|
||||||
// M117 - display message
|
// M117 - display message
|
||||||
|
@ -110,7 +109,8 @@
|
||||||
// M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
// M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
||||||
// M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
// M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
||||||
// M140 - Set bed target temp
|
// M140 - Set bed target temp
|
||||||
// M190 - Wait for bed current temp to reach target temp.
|
// M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
|
||||||
|
// Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
|
||||||
// M200 - Set filament diameter
|
// M200 - Set filament diameter
|
||||||
// M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
// M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
||||||
// M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
// M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
||||||
|
@ -125,10 +125,11 @@
|
||||||
// M220 S<factor in percent>- set speed factor override percentage
|
// M220 S<factor in percent>- set speed factor override percentage
|
||||||
// M221 S<factor in percent>- set extrude factor override percentage
|
// M221 S<factor in percent>- set extrude factor override percentage
|
||||||
// M240 - Trigger a camera to take a photograph
|
// M240 - Trigger a camera to take a photograph
|
||||||
|
// M250 - Set LCD contrast C<contrast value> (value 0..63)
|
||||||
// M280 - set servo position absolute. P: servo index, S: angle or microseconds
|
// M280 - set servo position absolute. P: servo index, S: angle or microseconds
|
||||||
// M300 - Play beepsound S<frequency Hz> P<duration ms>
|
// M300 - Play beepsound S<frequency Hz> P<duration ms>
|
||||||
// M301 - Set PID parameters P I and D
|
// M301 - Set PID parameters P I and D
|
||||||
// M302 - Allow cold extrudes
|
// M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
|
||||||
// M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
// M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
||||||
// M304 - Set bed PID parameters P I and D
|
// M304 - Set bed PID parameters P I and D
|
||||||
// M400 - Finish all moves
|
// M400 - Finish all moves
|
||||||
|
@ -177,6 +178,10 @@ float extruder_offset[2][EXTRUDERS] = {
|
||||||
#endif
|
#endif
|
||||||
uint8_t active_extruder = 0;
|
uint8_t active_extruder = 0;
|
||||||
int fanSpeed=0;
|
int fanSpeed=0;
|
||||||
|
#ifdef SERVO_ENDSTOPS
|
||||||
|
int servo_endstops[] = SERVO_ENDSTOPS;
|
||||||
|
int servo_endstop_angles[] = SERVO_ENDSTOP_ANGLES;
|
||||||
|
#endif
|
||||||
#ifdef BARICUDA
|
#ifdef BARICUDA
|
||||||
int ValvePressure=0;
|
int ValvePressure=0;
|
||||||
int EtoPPressure=0;
|
int EtoPPressure=0;
|
||||||
|
@ -194,6 +199,9 @@ int EtoPPressure=0;
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
|
const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
|
||||||
static float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0};
|
static float destination[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0};
|
||||||
|
#ifdef DELTA
|
||||||
|
static float delta[3] = {0.0, 0.0, 0.0};
|
||||||
|
#endif
|
||||||
static float offset[3] = {0.0, 0.0, 0.0};
|
static float offset[3] = {0.0, 0.0, 0.0};
|
||||||
static bool home_all_axis = true;
|
static bool home_all_axis = true;
|
||||||
static float feedrate = 1500.0, next_feedrate, saved_feedrate;
|
static float feedrate = 1500.0, next_feedrate, saved_feedrate;
|
||||||
|
@ -234,6 +242,9 @@ bool Stopped=false;
|
||||||
Servo servos[NUM_SERVOS];
|
Servo servos[NUM_SERVOS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
bool CooldownNoWait = true;
|
||||||
|
bool target_direction;
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================ROUTINES=============================
|
//=============================ROUTINES=============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -351,6 +362,16 @@ void servo_init()
|
||||||
#if (NUM_SERVOS >= 5)
|
#if (NUM_SERVOS >= 5)
|
||||||
#error "TODO: enter initalisation code for more servos"
|
#error "TODO: enter initalisation code for more servos"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Set position of Servo Endstops that are defined
|
||||||
|
#ifdef SERVO_ENDSTOPS
|
||||||
|
for(int8_t i = 0; i < 3; i++)
|
||||||
|
{
|
||||||
|
if(servo_endstops[i] > -1) {
|
||||||
|
servos[servo_endstops[i]].write(servo_endstop_angles[i * 2 + 1]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void setup()
|
void setup()
|
||||||
|
@ -404,6 +425,7 @@ void setup()
|
||||||
servo_init();
|
servo_init();
|
||||||
|
|
||||||
lcd_init();
|
lcd_init();
|
||||||
|
_delay_ms(1000); // wait 1sec to display the splash screen
|
||||||
|
|
||||||
#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
|
#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
|
||||||
SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
|
SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
|
||||||
|
@ -655,7 +677,44 @@ XYZ_CONSTS_FROM_CONFIG(float, max_length, MAX_LENGTH);
|
||||||
XYZ_CONSTS_FROM_CONFIG(float, home_retract_mm, HOME_RETRACT_MM);
|
XYZ_CONSTS_FROM_CONFIG(float, home_retract_mm, HOME_RETRACT_MM);
|
||||||
XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
|
XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
|
||||||
|
|
||||||
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
#if EXTRUDERS == 1 || defined(COREXY) \
|
||||||
|
|| !defined(X2_ENABLE_PIN) || !defined(X2_STEP_PIN) || !defined(X2_DIR_PIN) \
|
||||||
|
|| !defined(X2_HOME_POS) || !defined(X2_MIN_POS) || !defined(X2_MAX_POS) \
|
||||||
|
|| !defined(X_MAX_PIN) || X_MAX_PIN < 0
|
||||||
|
#error "Missing or invalid definitions for DUAL_X_CARRIAGE mode."
|
||||||
|
#endif
|
||||||
|
#if X_HOME_DIR != -1 || X2_HOME_DIR != 1
|
||||||
|
#error "Please use canonical x-carriage assignment" // the x-carriages are defined by their homing directions
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static float x_home_pos(int extruder) {
|
||||||
|
if (extruder == 0)
|
||||||
|
return base_home_pos(X_AXIS) + add_homeing[X_AXIS];
|
||||||
|
else
|
||||||
|
// In dual carriage mode the extruder offset provides an override of the
|
||||||
|
// second X-carriage offset when homed - otherwise X2_HOME_POS is used.
|
||||||
|
// This allow soft recalibration of the second extruder offset position without firmware reflash
|
||||||
|
// (through the M218 command).
|
||||||
|
return (extruder_offset[X_AXIS][1] > 0) ? extruder_offset[X_AXIS][1] : X2_HOME_POS;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int x_home_dir(int extruder) {
|
||||||
|
return (extruder == 0) ? X_HOME_DIR : X2_HOME_DIR;
|
||||||
|
}
|
||||||
|
|
||||||
|
static float inactive_x_carriage_pos = X2_MAX_POS;
|
||||||
|
#endif
|
||||||
|
|
||||||
static void axis_is_at_home(int axis) {
|
static void axis_is_at_home(int axis) {
|
||||||
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
if (axis == X_AXIS && active_extruder != 0) {
|
||||||
|
current_position[X_AXIS] = x_home_pos(active_extruder);
|
||||||
|
min_pos[X_AXIS] = X2_MIN_POS;
|
||||||
|
max_pos[X_AXIS] = max(extruder_offset[X_AXIS][1], X2_MAX_POS);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
current_position[axis] = base_home_pos(axis) + add_homeing[axis];
|
current_position[axis] = base_home_pos(axis) + add_homeing[axis];
|
||||||
min_pos[axis] = base_min_pos(axis) + add_homeing[axis];
|
min_pos[axis] = base_min_pos(axis) + add_homeing[axis];
|
||||||
max_pos[axis] = base_max_pos(axis) + add_homeing[axis];
|
max_pos[axis] = base_max_pos(axis) + add_homeing[axis];
|
||||||
|
@ -669,20 +728,33 @@ static void homeaxis(int axis) {
|
||||||
axis==Y_AXIS ? HOMEAXIS_DO(Y) :
|
axis==Y_AXIS ? HOMEAXIS_DO(Y) :
|
||||||
axis==Z_AXIS ? HOMEAXIS_DO(Z) :
|
axis==Z_AXIS ? HOMEAXIS_DO(Z) :
|
||||||
0) {
|
0) {
|
||||||
|
int axis_home_dir = home_dir(axis);
|
||||||
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
if (axis == X_AXIS)
|
||||||
|
axis_home_dir = x_home_dir(active_extruder);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Engage Servo endstop if enabled
|
||||||
|
#ifdef SERVO_ENDSTOPS
|
||||||
|
if (SERVO_ENDSTOPS[axis] > -1) {
|
||||||
|
servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
current_position[axis] = 0;
|
current_position[axis] = 0;
|
||||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||||
destination[axis] = 1.5 * max_length(axis) * home_dir(axis);
|
destination[axis] = 1.5 * max_length(axis) * axis_home_dir;
|
||||||
feedrate = homing_feedrate[axis];
|
feedrate = homing_feedrate[axis];
|
||||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
|
|
||||||
current_position[axis] = 0;
|
current_position[axis] = 0;
|
||||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||||
destination[axis] = -home_retract_mm(axis) * home_dir(axis);
|
destination[axis] = -home_retract_mm(axis) * axis_home_dir;
|
||||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
|
|
||||||
destination[axis] = 2*home_retract_mm(axis) * home_dir(axis);
|
destination[axis] = 2*home_retract_mm(axis) * axis_home_dir;
|
||||||
feedrate = homing_feedrate[axis]/2 ;
|
feedrate = homing_feedrate[axis]/2 ;
|
||||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
|
@ -691,6 +763,13 @@ static void homeaxis(int axis) {
|
||||||
destination[axis] = current_position[axis];
|
destination[axis] = current_position[axis];
|
||||||
feedrate = 0.0;
|
feedrate = 0.0;
|
||||||
endstops_hit_on_purpose();
|
endstops_hit_on_purpose();
|
||||||
|
|
||||||
|
// Retract Servo endstop if enabled
|
||||||
|
#ifdef SERVO_ENDSTOPS
|
||||||
|
if (SERVO_ENDSTOPS[axis] > -1) {
|
||||||
|
servos[servo_endstops[axis]].write(servo_endstop_angles[axis * 2 + 1]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
|
#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
|
||||||
|
@ -781,7 +860,40 @@ void process_commands()
|
||||||
for(int8_t i=0; i < NUM_AXIS; i++) {
|
for(int8_t i=0; i < NUM_AXIS; i++) {
|
||||||
destination[i] = current_position[i];
|
destination[i] = current_position[i];
|
||||||
}
|
}
|
||||||
feedrate = 0.0;
|
feedrate = 0.0;
|
||||||
|
|
||||||
|
#ifdef DELTA
|
||||||
|
// A delta can only safely home all axis at the same time
|
||||||
|
// all axis have to home at the same time
|
||||||
|
|
||||||
|
// Move all carriages up together until the first endstop is hit.
|
||||||
|
current_position[X_AXIS] = 0;
|
||||||
|
current_position[Y_AXIS] = 0;
|
||||||
|
current_position[Z_AXIS] = 0;
|
||||||
|
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||||
|
|
||||||
|
destination[X_AXIS] = 3 * Z_MAX_LENGTH;
|
||||||
|
destination[Y_AXIS] = 3 * Z_MAX_LENGTH;
|
||||||
|
destination[Z_AXIS] = 3 * Z_MAX_LENGTH;
|
||||||
|
feedrate = 1.732 * homing_feedrate[X_AXIS];
|
||||||
|
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
||||||
|
st_synchronize();
|
||||||
|
endstops_hit_on_purpose();
|
||||||
|
|
||||||
|
current_position[X_AXIS] = destination[X_AXIS];
|
||||||
|
current_position[Y_AXIS] = destination[Y_AXIS];
|
||||||
|
current_position[Z_AXIS] = destination[Z_AXIS];
|
||||||
|
|
||||||
|
// take care of back off and rehome now we are all at the top
|
||||||
|
HOMEAXIS(X);
|
||||||
|
HOMEAXIS(Y);
|
||||||
|
HOMEAXIS(Z);
|
||||||
|
|
||||||
|
calculate_delta(current_position);
|
||||||
|
plan_set_position(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], current_position[E_AXIS]);
|
||||||
|
|
||||||
|
#else // NOT DELTA
|
||||||
|
|
||||||
home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
|
home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
|
||||||
|
|
||||||
#if Z_HOME_DIR > 0 // If homing away from BED do Z first
|
#if Z_HOME_DIR > 0 // If homing away from BED do Z first
|
||||||
|
@ -795,8 +907,14 @@ void process_commands()
|
||||||
{
|
{
|
||||||
current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
|
current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
|
||||||
|
|
||||||
|
#ifndef DUAL_X_CARRIAGE
|
||||||
|
int x_axis_home_dir = home_dir(X_AXIS);
|
||||||
|
#else
|
||||||
|
int x_axis_home_dir = x_home_dir(active_extruder);
|
||||||
|
#endif
|
||||||
|
|
||||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||||
destination[X_AXIS] = 1.5 * X_MAX_LENGTH * X_HOME_DIR;destination[Y_AXIS] = 1.5 * Y_MAX_LENGTH * Y_HOME_DIR;
|
destination[X_AXIS] = 1.5 * max_length(X_AXIS) * x_axis_home_dir;destination[Y_AXIS] = 1.5 * max_length(Y_AXIS) * home_dir(Y_AXIS);
|
||||||
feedrate = homing_feedrate[X_AXIS];
|
feedrate = homing_feedrate[X_AXIS];
|
||||||
if(homing_feedrate[Y_AXIS]<feedrate)
|
if(homing_feedrate[Y_AXIS]<feedrate)
|
||||||
feedrate =homing_feedrate[Y_AXIS];
|
feedrate =homing_feedrate[Y_AXIS];
|
||||||
|
@ -812,11 +930,22 @@ void process_commands()
|
||||||
feedrate = 0.0;
|
feedrate = 0.0;
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
endstops_hit_on_purpose();
|
endstops_hit_on_purpose();
|
||||||
|
|
||||||
|
current_position[X_AXIS] = destination[X_AXIS];
|
||||||
|
current_position[Y_AXIS] = destination[Y_AXIS];
|
||||||
|
current_position[Z_AXIS] = destination[Z_AXIS];
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
|
if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
|
||||||
{
|
{
|
||||||
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
int tmp_extruder = active_extruder;
|
||||||
|
active_extruder = !active_extruder;
|
||||||
|
HOMEAXIS(X);
|
||||||
|
inactive_x_carriage_pos = current_position[X_AXIS];
|
||||||
|
active_extruder = tmp_extruder;
|
||||||
|
#endif
|
||||||
HOMEAXIS(X);
|
HOMEAXIS(X);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -849,7 +978,8 @@ void process_commands()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||||
|
#endif // else DELTA
|
||||||
|
|
||||||
#ifdef ENDSTOPS_ONLY_FOR_HOMING
|
#ifdef ENDSTOPS_ONLY_FOR_HOMING
|
||||||
enable_endstops(false);
|
enable_endstops(false);
|
||||||
#endif
|
#endif
|
||||||
|
@ -988,6 +1118,19 @@ void process_commands()
|
||||||
card.removeFile(strchr_pointer + 4);
|
card.removeFile(strchr_pointer + 4);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
case 32: //M32 - Select file and start SD print
|
||||||
|
if(card.sdprinting) {
|
||||||
|
st_synchronize();
|
||||||
|
card.closefile();
|
||||||
|
card.sdprinting = false;
|
||||||
|
}
|
||||||
|
starpos = (strchr(strchr_pointer + 4,'*'));
|
||||||
|
if(starpos!=NULL)
|
||||||
|
*(starpos-1)='\0';
|
||||||
|
card.openFile(strchr_pointer + 4,true);
|
||||||
|
card.startFileprint();
|
||||||
|
starttime=millis();
|
||||||
|
break;
|
||||||
case 928: //M928 - Start SD write
|
case 928: //M928 - Start SD write
|
||||||
starpos = (strchr(strchr_pointer + 5,'*'));
|
starpos = (strchr(strchr_pointer + 5,'*'));
|
||||||
if(starpos != NULL){
|
if(starpos != NULL){
|
||||||
|
@ -1055,7 +1198,7 @@ void process_commands()
|
||||||
case 105 : // M105
|
case 105 : // M105
|
||||||
if(setTargetedHotend(105)){
|
if(setTargetedHotend(105)){
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
|
#if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
|
||||||
SERIAL_PROTOCOLPGM("ok T:");
|
SERIAL_PROTOCOLPGM("ok T:");
|
||||||
SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
|
SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
|
||||||
|
@ -1098,7 +1241,13 @@ void process_commands()
|
||||||
#ifdef AUTOTEMP
|
#ifdef AUTOTEMP
|
||||||
autotemp_enabled=false;
|
autotemp_enabled=false;
|
||||||
#endif
|
#endif
|
||||||
if (code_seen('S')) setTargetHotend(code_value(), tmp_extruder);
|
if (code_seen('S')) {
|
||||||
|
setTargetHotend(code_value(), tmp_extruder);
|
||||||
|
CooldownNoWait = true;
|
||||||
|
} else if (code_seen('R')) {
|
||||||
|
setTargetHotend(code_value(), tmp_extruder);
|
||||||
|
CooldownNoWait = false;
|
||||||
|
}
|
||||||
#ifdef AUTOTEMP
|
#ifdef AUTOTEMP
|
||||||
if (code_seen('S')) autotemp_min=code_value();
|
if (code_seen('S')) autotemp_min=code_value();
|
||||||
if (code_seen('B')) autotemp_max=code_value();
|
if (code_seen('B')) autotemp_max=code_value();
|
||||||
|
@ -1113,7 +1262,7 @@ void process_commands()
|
||||||
codenum = millis();
|
codenum = millis();
|
||||||
|
|
||||||
/* See if we are heating up or cooling down */
|
/* See if we are heating up or cooling down */
|
||||||
bool target_direction = isHeatingHotend(tmp_extruder); // true if heating, false if cooling
|
target_direction = isHeatingHotend(tmp_extruder); // true if heating, false if cooling
|
||||||
|
|
||||||
#ifdef TEMP_RESIDENCY_TIME
|
#ifdef TEMP_RESIDENCY_TIME
|
||||||
long residencyStart;
|
long residencyStart;
|
||||||
|
@ -1169,9 +1318,18 @@ void process_commands()
|
||||||
case 190: // M190 - Wait for bed heater to reach target.
|
case 190: // M190 - Wait for bed heater to reach target.
|
||||||
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
|
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
|
||||||
LCD_MESSAGEPGM(MSG_BED_HEATING);
|
LCD_MESSAGEPGM(MSG_BED_HEATING);
|
||||||
if (code_seen('S')) setTargetBed(code_value());
|
if (code_seen('S')) {
|
||||||
|
setTargetBed(code_value());
|
||||||
|
CooldownNoWait = true;
|
||||||
|
} else if (code_seen('R')) {
|
||||||
|
setTargetBed(code_value());
|
||||||
|
CooldownNoWait = false;
|
||||||
|
}
|
||||||
codenum = millis();
|
codenum = millis();
|
||||||
while(isHeatingBed())
|
|
||||||
|
target_direction = isHeatingBed(); // true if heating, false if cooling
|
||||||
|
|
||||||
|
while ( target_direction ? (isHeatingBed()) : (isCoolingBed()&&(CooldownNoWait==false)) )
|
||||||
{
|
{
|
||||||
if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
|
if(( millis() - codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
|
||||||
{
|
{
|
||||||
|
@ -1550,17 +1708,22 @@ void process_commands()
|
||||||
#if LARGE_FLASH == true && ( BEEPER > 0 || defined(ULTRALCD) )
|
#if LARGE_FLASH == true && ( BEEPER > 0 || defined(ULTRALCD) )
|
||||||
case 300: // M300
|
case 300: // M300
|
||||||
{
|
{
|
||||||
int beepS = 400;
|
int beepS = code_seen('S') ? code_value() : 110;
|
||||||
int beepP = 1000;
|
int beepP = code_seen('P') ? code_value() : 1000;
|
||||||
if(code_seen('S')) beepS = code_value();
|
if (beepS > 0)
|
||||||
if(code_seen('P')) beepP = code_value();
|
{
|
||||||
#if BEEPER > 0
|
#if BEEPER > 0
|
||||||
tone(BEEPER, beepS);
|
tone(BEEPER, beepS);
|
||||||
|
delay(beepP);
|
||||||
|
noTone(BEEPER);
|
||||||
|
#elif defined(ULTRALCD)
|
||||||
|
lcd_buzz(beepS, beepP);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
delay(beepP);
|
delay(beepP);
|
||||||
noTone(BEEPER);
|
}
|
||||||
#elif defined(ULTRALCD)
|
|
||||||
lcd_buzz(beepS, beepP);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif // M300
|
#endif // M300
|
||||||
|
@ -1633,12 +1796,27 @@ void process_commands()
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#ifdef DOGLCD
|
||||||
case 302: // allow cold extrudes
|
case 250: // M250 Set LCD contrast value: C<value> (value 0..63)
|
||||||
|
{
|
||||||
|
if (code_seen('C')) {
|
||||||
|
lcd_setcontrast( ((int)code_value())&63 );
|
||||||
|
}
|
||||||
|
SERIAL_PROTOCOLPGM("lcd contrast value: ");
|
||||||
|
SERIAL_PROTOCOL(lcd_contrast);
|
||||||
|
SERIAL_PROTOCOLLN("");
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
|
case 302: // allow cold extrudes, or set the minimum extrude temperature
|
||||||
{
|
{
|
||||||
allow_cold_extrudes(true);
|
float temp = .0;
|
||||||
|
if (code_seen('S')) temp=code_value();
|
||||||
|
set_extrude_min_temp(temp);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
case 303: // M303 PID autotune
|
case 303: // M303 PID autotune
|
||||||
{
|
{
|
||||||
float temp = 150.0;
|
float temp = 150.0;
|
||||||
|
@ -1887,6 +2065,20 @@ void process_commands()
|
||||||
if(tmp_extruder != active_extruder) {
|
if(tmp_extruder != active_extruder) {
|
||||||
// Save current position to return to after applying extruder offset
|
// Save current position to return to after applying extruder offset
|
||||||
memcpy(destination, current_position, sizeof(destination));
|
memcpy(destination, current_position, sizeof(destination));
|
||||||
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
// only apply Y extruder offset in dual x carriage mode (x offset is already used in determining home pos)
|
||||||
|
current_position[Y_AXIS] = current_position[Y_AXIS] -
|
||||||
|
extruder_offset[Y_AXIS][active_extruder] +
|
||||||
|
extruder_offset[Y_AXIS][tmp_extruder];
|
||||||
|
|
||||||
|
float tmp_x_pos = current_position[X_AXIS];
|
||||||
|
|
||||||
|
// Set the new active extruder and position
|
||||||
|
active_extruder = tmp_extruder;
|
||||||
|
axis_is_at_home(X_AXIS); //this function updates X min/max values.
|
||||||
|
current_position[X_AXIS] = inactive_x_carriage_pos;
|
||||||
|
inactive_x_carriage_pos = tmp_x_pos;
|
||||||
|
#else
|
||||||
// Offset extruder (only by XY)
|
// Offset extruder (only by XY)
|
||||||
int i;
|
int i;
|
||||||
for(i = 0; i < 2; i++) {
|
for(i = 0; i < 2; i++) {
|
||||||
|
@ -1896,6 +2088,7 @@ void process_commands()
|
||||||
}
|
}
|
||||||
// Set the new active extruder and position
|
// Set the new active extruder and position
|
||||||
active_extruder = tmp_extruder;
|
active_extruder = tmp_extruder;
|
||||||
|
#endif //else DUAL_X_CARRIAGE
|
||||||
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
|
||||||
// Move to the old position if 'F' was in the parameters
|
// Move to the old position if 'F' was in the parameters
|
||||||
if(make_move && Stopped == false) {
|
if(make_move && Stopped == false) {
|
||||||
|
@ -2032,11 +2225,64 @@ void clamp_to_software_endstops(float target[3])
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef DELTA
|
||||||
|
void calculate_delta(float cartesian[3])
|
||||||
|
{
|
||||||
|
delta[X_AXIS] = sqrt(sq(DELTA_DIAGONAL_ROD)
|
||||||
|
- sq(DELTA_TOWER1_X-cartesian[X_AXIS])
|
||||||
|
- sq(DELTA_TOWER1_Y-cartesian[Y_AXIS])
|
||||||
|
) + cartesian[Z_AXIS];
|
||||||
|
delta[Y_AXIS] = sqrt(sq(DELTA_DIAGONAL_ROD)
|
||||||
|
- sq(DELTA_TOWER2_X-cartesian[X_AXIS])
|
||||||
|
- sq(DELTA_TOWER2_Y-cartesian[Y_AXIS])
|
||||||
|
) + cartesian[Z_AXIS];
|
||||||
|
delta[Z_AXIS] = sqrt(sq(DELTA_DIAGONAL_ROD)
|
||||||
|
- sq(DELTA_TOWER3_X-cartesian[X_AXIS])
|
||||||
|
- sq(DELTA_TOWER3_Y-cartesian[Y_AXIS])
|
||||||
|
) + cartesian[Z_AXIS];
|
||||||
|
/*
|
||||||
|
SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
|
||||||
|
SERIAL_ECHOPGM(" y="); SERIAL_ECHO(cartesian[Y_AXIS]);
|
||||||
|
SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(cartesian[Z_AXIS]);
|
||||||
|
|
||||||
|
SERIAL_ECHOPGM("delta x="); SERIAL_ECHO(delta[X_AXIS]);
|
||||||
|
SERIAL_ECHOPGM(" y="); SERIAL_ECHO(delta[Y_AXIS]);
|
||||||
|
SERIAL_ECHOPGM(" z="); SERIAL_ECHOLN(delta[Z_AXIS]);
|
||||||
|
*/
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void prepare_move()
|
void prepare_move()
|
||||||
{
|
{
|
||||||
clamp_to_software_endstops(destination);
|
clamp_to_software_endstops(destination);
|
||||||
|
|
||||||
previous_millis_cmd = millis();
|
previous_millis_cmd = millis();
|
||||||
|
#ifdef DELTA
|
||||||
|
float difference[NUM_AXIS];
|
||||||
|
for (int8_t i=0; i < NUM_AXIS; i++) {
|
||||||
|
difference[i] = destination[i] - current_position[i];
|
||||||
|
}
|
||||||
|
float cartesian_mm = sqrt(sq(difference[X_AXIS]) +
|
||||||
|
sq(difference[Y_AXIS]) +
|
||||||
|
sq(difference[Z_AXIS]));
|
||||||
|
if (cartesian_mm < 0.000001) { cartesian_mm = abs(difference[E_AXIS]); }
|
||||||
|
if (cartesian_mm < 0.000001) { return; }
|
||||||
|
float seconds = 6000 * cartesian_mm / feedrate / feedmultiply;
|
||||||
|
int steps = max(1, int(DELTA_SEGMENTS_PER_SECOND * seconds));
|
||||||
|
// SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
|
||||||
|
// SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
|
||||||
|
// SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
|
||||||
|
for (int s = 1; s <= steps; s++) {
|
||||||
|
float fraction = float(s) / float(steps);
|
||||||
|
for(int8_t i=0; i < NUM_AXIS; i++) {
|
||||||
|
destination[i] = current_position[i] + difference[i] * fraction;
|
||||||
|
}
|
||||||
|
calculate_delta(destination);
|
||||||
|
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS],
|
||||||
|
destination[E_AXIS], feedrate*feedmultiply/60/100.0,
|
||||||
|
active_extruder);
|
||||||
|
}
|
||||||
|
#else
|
||||||
// Do not use feedmultiply for E or Z only moves
|
// Do not use feedmultiply for E or Z only moves
|
||||||
if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
|
if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
|
||||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
|
||||||
|
@ -2044,6 +2290,7 @@ void prepare_move()
|
||||||
else {
|
else {
|
||||||
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
|
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
for(int8_t i=0; i < NUM_AXIS; i++) {
|
for(int8_t i=0; i < NUM_AXIS; i++) {
|
||||||
current_position[i] = destination[i];
|
current_position[i] = destination[i];
|
||||||
}
|
}
|
||||||
|
@ -2086,6 +2333,9 @@ void controllerFan()
|
||||||
|| !READ(E2_ENABLE_PIN)
|
|| !READ(E2_ENABLE_PIN)
|
||||||
#endif
|
#endif
|
||||||
#if EXTRUDER > 1
|
#if EXTRUDER > 1
|
||||||
|
#if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
|
||||||
|
|| !READ(X2_ENABLE_PIN)
|
||||||
|
#endif
|
||||||
|| !READ(E1_ENABLE_PIN)
|
|| !READ(E1_ENABLE_PIN)
|
||||||
#endif
|
#endif
|
||||||
|| !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled...
|
|| !READ(E0_ENABLE_PIN)) //If any of the drivers are enabled...
|
||||||
|
@ -2287,3 +2537,4 @@ bool setTargetedHotend(int code){
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -41,6 +41,8 @@
|
||||||
detach() - Stops an attached servos from pulsing its i/o pin.
|
detach() - Stops an attached servos from pulsing its i/o pin.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
|
#include "Configuration.h"
|
||||||
|
|
||||||
#ifdef NUM_SERVOS
|
#ifdef NUM_SERVOS
|
||||||
#include <avr/interrupt.h>
|
#include <avr/interrupt.h>
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
|
|
|
@ -18,6 +18,8 @@ CardReader::CardReader()
|
||||||
saving = false;
|
saving = false;
|
||||||
logging = false;
|
logging = false;
|
||||||
autostart_atmillis=0;
|
autostart_atmillis=0;
|
||||||
|
workDirDepth = 0;
|
||||||
|
memset(workDirParents, 0, sizeof(workDirParents));
|
||||||
|
|
||||||
autostart_stilltocheck=true; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
|
autostart_stilltocheck=true; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
|
||||||
lastnr=0;
|
lastnr=0;
|
||||||
|
@ -204,7 +206,6 @@ void CardReader::startFileprint()
|
||||||
if(cardOK)
|
if(cardOK)
|
||||||
{
|
{
|
||||||
sdprinting = true;
|
sdprinting = true;
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -521,19 +522,24 @@ void CardReader::chdir(const char * relpath)
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
workDirParentParent=workDirParent;
|
if (workDirDepth < MAX_DIR_DEPTH) {
|
||||||
workDirParent=*parent;
|
for (int d = ++workDirDepth; d--;)
|
||||||
|
workDirParents[d+1] = workDirParents[d];
|
||||||
|
workDirParents[0]=*parent;
|
||||||
|
}
|
||||||
workDir=newfile;
|
workDir=newfile;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void CardReader::updir()
|
void CardReader::updir()
|
||||||
{
|
{
|
||||||
if(!workDir.isRoot())
|
if(workDirDepth > 0)
|
||||||
{
|
{
|
||||||
workDir=workDirParent;
|
--workDirDepth;
|
||||||
workDirParent=workDirParentParent;
|
workDir = workDirParents[0];
|
||||||
|
int d;
|
||||||
|
for (int d = 0; d < workDirDepth; d++)
|
||||||
|
workDirParents[d] = workDirParents[d+1];
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -3,6 +3,8 @@
|
||||||
|
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
|
|
||||||
|
#define MAX_DIR_DEPTH 10
|
||||||
|
|
||||||
#include "SdFile.h"
|
#include "SdFile.h"
|
||||||
enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename};
|
enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename};
|
||||||
class CardReader
|
class CardReader
|
||||||
|
@ -53,7 +55,8 @@ public:
|
||||||
bool filenameIsDir;
|
bool filenameIsDir;
|
||||||
int lastnr; //last number of the autostart;
|
int lastnr; //last number of the autostart;
|
||||||
private:
|
private:
|
||||||
SdFile root,*curDir,workDir,workDirParent,workDirParentParent;
|
SdFile root,*curDir,workDir,workDirParents[MAX_DIR_DEPTH];
|
||||||
|
uint16_t workDirDepth;
|
||||||
Sd2Card card;
|
Sd2Card card;
|
||||||
SdVolume volume;
|
SdVolume volume;
|
||||||
SdFile file;
|
SdFile file;
|
||||||
|
|
|
@ -33,11 +33,11 @@
|
||||||
#define LCD_CLICKED (buttons&EN_C)
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// CHANGE_DE begin ***
|
#include <U8glib.h>
|
||||||
#include <U8glib.h> // DE_U8glib
|
|
||||||
#include "DOGMbitmaps.h"
|
#include "DOGMbitmaps.h"
|
||||||
#include "dogm_font_data_marlin.h"
|
#include "dogm_font_data_marlin.h"
|
||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
|
#include "ultralcd_st7920_u8glib_rrd.h"
|
||||||
|
|
||||||
|
|
||||||
/* Russian language not supported yet, needs custom font
|
/* Russian language not supported yet, needs custom font
|
||||||
|
@ -74,17 +74,28 @@
|
||||||
|
|
||||||
#define FONT_STATUSMENU u8g_font_6x9
|
#define FONT_STATUSMENU u8g_font_6x9
|
||||||
|
|
||||||
|
int lcd_contrast;
|
||||||
|
|
||||||
// LCD selection
|
// LCD selection
|
||||||
#ifdef U8GLIB_ST7920
|
#ifdef U8GLIB_ST7920
|
||||||
// SPI Com: SCK = en = (D4), MOSI = rw = (RS), CS = di = (ENABLE)
|
//U8GLIB_ST7920_128X64_RRD u8g(0,0,0);
|
||||||
U8GLIB_ST7920_128X64_1X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS);
|
U8GLIB_ST7920_128X64_RRD u8g(0);
|
||||||
|
#elif defined(MAKRPANEL)
|
||||||
|
// The MaKrPanel display, ST7565 controller as well
|
||||||
|
U8GLIB_NHD_C12864 u8g(DOGLCD_CS, DOGLCD_A0);
|
||||||
#else
|
#else
|
||||||
|
// for regular DOGM128 display with HW-SPI
|
||||||
U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0
|
U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0); // HW-SPI Com: CS, A0
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static void lcd_implementation_init()
|
static void lcd_implementation_init()
|
||||||
{
|
{
|
||||||
|
#ifdef LCD_PIN_BL
|
||||||
|
pinMode(LCD_PIN_BL, OUTPUT); // Enable LCD backlight
|
||||||
|
digitalWrite(LCD_PIN_BL, HIGH);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
u8g.setContrast(lcd_contrast);
|
||||||
// Uncomment this if you have the first generation (V1.10) of STBs board
|
// Uncomment this if you have the first generation (V1.10) of STBs board
|
||||||
// pinMode(17, OUTPUT); // Enable LCD backlight
|
// pinMode(17, OUTPUT); // Enable LCD backlight
|
||||||
// digitalWrite(17, HIGH);
|
// digitalWrite(17, HIGH);
|
||||||
|
@ -118,14 +129,14 @@ static void lcd_implementation_init()
|
||||||
u8g.setFont(u8g_font_6x10_marlin);
|
u8g.setFont(u8g_font_6x10_marlin);
|
||||||
u8g.drawStr(62,10,"MARLIN");
|
u8g.drawStr(62,10,"MARLIN");
|
||||||
u8g.setFont(u8g_font_5x8);
|
u8g.setFont(u8g_font_5x8);
|
||||||
u8g.drawStr(62,19,"V1.0.0 RC2");
|
u8g.drawStr(62,19,"V1.0.0 RC2-mm");
|
||||||
u8g.setFont(u8g_font_6x10_marlin);
|
u8g.setFont(u8g_font_6x10_marlin);
|
||||||
u8g.drawStr(62,28,"by ErikZalm");
|
u8g.drawStr(62,28,"by ErikZalm");
|
||||||
u8g.drawStr(62,41,"DOGM128 LCD");
|
u8g.drawStr(62,41,"DOGM128 LCD");
|
||||||
u8g.setFont(u8g_font_5x8);
|
u8g.setFont(u8g_font_5x8);
|
||||||
u8g.drawStr(62,48,"enhancements");
|
u8g.drawStr(62,48,"enhancements");
|
||||||
u8g.setFont(u8g_font_5x8);
|
u8g.setFont(u8g_font_5x8);
|
||||||
u8g.drawStr(62,55,"by STB");
|
u8g.drawStr(62,55,"by STB, MM");
|
||||||
u8g.drawStr(62,61,"uses u");
|
u8g.drawStr(62,61,"uses u");
|
||||||
u8g.drawStr90(92,57,"8");
|
u8g.drawStr90(92,57,"8");
|
||||||
u8g.drawStr(100,61,"glib");
|
u8g.drawStr(100,61,"glib");
|
||||||
|
|
|
@ -3,13 +3,13 @@
|
||||||
|
|
||||||
// NOTE: IF YOU CHANGE THIS FILE / MERGE THIS FILE WITH CHANGES
|
// NOTE: IF YOU CHANGE THIS FILE / MERGE THIS FILE WITH CHANGES
|
||||||
//
|
//
|
||||||
// ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRALCD" / "SDSUPPORT" #define IN "Configuration.h"
|
// ==> ALWAYS TRY TO COMPILE MARLIN WITH/WITHOUT "ULTIPANEL" / "ULTRALCD" / "SDSUPPORT" #define IN "Configuration.h"
|
||||||
// ==> ALSO TRY ALL AVAILABLE "LANGUAGE_CHOICE" OPTIONS
|
// ==> ALSO TRY ALL AVAILABLE "LANGUAGE_CHOICE" OPTIONS
|
||||||
|
|
||||||
// Languages
|
// Languages
|
||||||
// 1 English
|
// 1 English
|
||||||
// 2 Polish
|
// 2 Polish
|
||||||
// 3 French (awaiting translation!)
|
// 3 French
|
||||||
// 4 German
|
// 4 German
|
||||||
// 5 Spanish
|
// 5 Spanish
|
||||||
// 6 Russian
|
// 6 Russian
|
||||||
|
@ -29,8 +29,15 @@
|
||||||
#elif MOTHERBOARD == 80
|
#elif MOTHERBOARD == 80
|
||||||
#define MACHINE_NAME "Rumba"
|
#define MACHINE_NAME "Rumba"
|
||||||
#define FIRMWARE_URL "https://github.com/ErikZalm/Marlin/"
|
#define FIRMWARE_URL "https://github.com/ErikZalm/Marlin/"
|
||||||
|
#elif MOTHERBOARD == 77
|
||||||
|
#define MACHINE_NAME "3Drag"
|
||||||
|
#define FIRMWARE_URL "http://3dprint.elettronicain.it/"
|
||||||
#else
|
#else
|
||||||
#define MACHINE_NAME "Mendel"
|
#ifdef CUSTOM_MENDEL_NAME
|
||||||
|
#define MACHINE_NAME CUSTOM_MENDEL_NAME
|
||||||
|
#else
|
||||||
|
#define MACHINE_NAME "Mendel"
|
||||||
|
#endif
|
||||||
#define FIRMWARE_URL "http://www.mendel-parts.com"
|
#define FIRMWARE_URL "http://www.mendel-parts.com"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -75,9 +82,9 @@
|
||||||
#define MSG_PID_D "PID-D"
|
#define MSG_PID_D "PID-D"
|
||||||
#define MSG_PID_C "PID-C"
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC "Accel"
|
#define MSG_ACC "Accel"
|
||||||
#define MSG_VXY_JERK "Vxy-jerk"
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX "Vmax "
|
#define MSG_VMAX "Vmax "
|
||||||
#define MSG_X "x"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y"
|
#define MSG_Y "y"
|
||||||
|
@ -94,6 +101,7 @@
|
||||||
#define MSG_RECTRACT "Rectract"
|
#define MSG_RECTRACT "Rectract"
|
||||||
#define MSG_TEMPERATURE "Temperature"
|
#define MSG_TEMPERATURE "Temperature"
|
||||||
#define MSG_MOTION "Motion"
|
#define MSG_MOTION "Motion"
|
||||||
|
#define MSG_CONTRAST "LCD contrast"
|
||||||
#define MSG_STORE_EPROM "Store memory"
|
#define MSG_STORE_EPROM "Store memory"
|
||||||
#define MSG_LOAD_EPROM "Load memory"
|
#define MSG_LOAD_EPROM "Load memory"
|
||||||
#define MSG_RESTORE_FAILSAFE "Restore Failsafe"
|
#define MSG_RESTORE_FAILSAFE "Restore Failsafe"
|
||||||
|
@ -188,7 +196,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Steprate to high: "
|
#define MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||||
|
@ -235,8 +243,8 @@
|
||||||
#define MSG_PID_C "PID-C"
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC "Acc"
|
#define MSG_ACC "Acc"
|
||||||
#define MSG_VXY_JERK "Zryw Vxy"
|
#define MSG_VXY_JERK "Zryw Vxy"
|
||||||
#define MSG_VZ_JERK "Zryw Vz"
|
#define MSG_VZ_JERK "Zryw Vz"
|
||||||
#define MSG_VE_JERK "Zryw Ve"
|
#define MSG_VE_JERK "Zryw Ve"
|
||||||
#define MSG_VMAX "Vmax"
|
#define MSG_VMAX "Vmax"
|
||||||
#define MSG_X "x"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y"
|
#define MSG_Y "y"
|
||||||
|
@ -253,6 +261,7 @@
|
||||||
#define MSG_RECTRACT "Wycofanie"
|
#define MSG_RECTRACT "Wycofanie"
|
||||||
#define MSG_TEMPERATURE "Temperatura"
|
#define MSG_TEMPERATURE "Temperatura"
|
||||||
#define MSG_MOTION "Ruch"
|
#define MSG_MOTION "Ruch"
|
||||||
|
#define MSG_CONTRAST "LCD contrast"
|
||||||
#define MSG_STORE_EPROM "Zapisz w pamieci"
|
#define MSG_STORE_EPROM "Zapisz w pamieci"
|
||||||
#define MSG_LOAD_EPROM "Wczytaj z pamieci"
|
#define MSG_LOAD_EPROM "Wczytaj z pamieci"
|
||||||
#define MSG_RESTORE_FAILSAFE " Ustawienia fabryczne"
|
#define MSG_RESTORE_FAILSAFE " Ustawienia fabryczne"
|
||||||
|
@ -348,7 +357,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "blad podczas zapisu do pliku"
|
#define MSG_SD_ERR_WRITE_TO_FILE "blad podczas zapisu do pliku"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Nie mozna odczytac podkatalogu: "
|
#define MSG_SD_CANT_ENTER_SUBDIR "Nie mozna odczytac podkatalogu: "
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Za duza czestotliwosc krokow: "
|
#define MSG_STEPPER_TOO_HIGH "Za duza czestotliwosc krokow: "
|
||||||
#define MSG_ENDSTOPS_HIT "Wylacznik krancowy zostal wyzwolony na pozycji: "
|
#define MSG_ENDSTOPS_HIT "Wylacznik krancowy zostal wyzwolony na pozycji: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " uniemozliwiono zimna ekstruzje"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " uniemozliwiono zimna ekstruzje"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " uniemozliwiono zbyt dluga ekstruzje"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " uniemozliwiono zbyt dluga ekstruzje"
|
||||||
|
@ -396,8 +405,8 @@
|
||||||
#define MSG_PID_C " PID-C: "
|
#define MSG_PID_C " PID-C: "
|
||||||
#define MSG_ACC " Acc:"
|
#define MSG_ACC " Acc:"
|
||||||
#define MSG_VXY_JERK "Vxy-jerk"
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX " Vmax "
|
#define MSG_VMAX " Vmax "
|
||||||
#define MSG_X "x:"
|
#define MSG_X "x:"
|
||||||
#define MSG_Y "y:"
|
#define MSG_Y "y:"
|
||||||
|
@ -416,6 +425,7 @@
|
||||||
#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
|
#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
|
||||||
#define MSG_TEMPERATURE_RTN " Temperature \003"
|
#define MSG_TEMPERATURE_RTN " Temperature \003"
|
||||||
#define MSG_MOTION_WIDE " Mouvement \x7E"
|
#define MSG_MOTION_WIDE " Mouvement \x7E"
|
||||||
|
#define MSG_CONTRAST "LCD contrast"
|
||||||
#define MSG_STORE_EPROM " Sauvegarder memoire"
|
#define MSG_STORE_EPROM " Sauvegarder memoire"
|
||||||
#define MSG_LOAD_EPROM " Lire memoire"
|
#define MSG_LOAD_EPROM " Lire memoire"
|
||||||
#define MSG_RESTORE_FAILSAFE " Restaurer memoire"
|
#define MSG_RESTORE_FAILSAFE " Restaurer memoire"
|
||||||
|
@ -512,7 +522,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "Erreur d'ecriture dans le fichier"
|
#define MSG_SD_ERR_WRITE_TO_FILE "Erreur d'ecriture dans le fichier"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Impossible d'entrer dans le sous-repertoire: "
|
#define MSG_SD_CANT_ENTER_SUBDIR "Impossible d'entrer dans le sous-repertoire: "
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Steprate trop eleve: "
|
#define MSG_STEPPER_TOO_HIGH "Steprate trop eleve: "
|
||||||
#define MSG_ENDSTOPS_HIT "Fin de course atteint: "
|
#define MSG_ENDSTOPS_HIT "Fin de course atteint: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " Extrusion a froid evitee"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " Extrusion a froid evitee"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " Extrusion longue evitee"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " Extrusion longue evitee"
|
||||||
|
@ -528,7 +538,7 @@
|
||||||
|
|
||||||
#define MSG_SD_INSERTED "SDKarte erkannt"
|
#define MSG_SD_INSERTED "SDKarte erkannt"
|
||||||
#define MSG_SD_REMOVED "SDKarte entfernt"
|
#define MSG_SD_REMOVED "SDKarte entfernt"
|
||||||
#define MSG_MAIN "Hauptmneü"
|
#define MSG_MAIN "Hauptmenü"
|
||||||
#define MSG_AUTOSTART "Autostart"
|
#define MSG_AUTOSTART "Autostart"
|
||||||
#define MSG_DISABLE_STEPPERS "Stepper abschalten"
|
#define MSG_DISABLE_STEPPERS "Stepper abschalten"
|
||||||
#define MSG_AUTO_HOME "Auto Nullpunkt"
|
#define MSG_AUTO_HOME "Auto Nullpunkt"
|
||||||
|
@ -547,7 +557,7 @@
|
||||||
#define MSG_NOZZLE2 "Düse3"
|
#define MSG_NOZZLE2 "Düse3"
|
||||||
#define MSG_BED "Bett"
|
#define MSG_BED "Bett"
|
||||||
#define MSG_FAN_SPEED "Lüftergeschw."
|
#define MSG_FAN_SPEED "Lüftergeschw."
|
||||||
#define MSG_FLOW "Fluß"
|
#define MSG_FLOW "Fluss"
|
||||||
#define MSG_CONTROL "Einstellungen"
|
#define MSG_CONTROL "Einstellungen"
|
||||||
#define MSG_MIN "\002 Min"
|
#define MSG_MIN "\002 Min"
|
||||||
#define MSG_MAX "\002 Max"
|
#define MSG_MAX "\002 Max"
|
||||||
|
@ -561,8 +571,8 @@
|
||||||
#define MSG_PID_C "PID-C"
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC "Acc"
|
#define MSG_ACC "Acc"
|
||||||
#define MSG_VXY_JERK "Vxy-jerk"
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX "Vmax "
|
#define MSG_VMAX "Vmax "
|
||||||
#define MSG_X "x"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y"
|
#define MSG_Y "y"
|
||||||
|
@ -580,6 +590,7 @@
|
||||||
#define MSG_WATCH "Beobachten"
|
#define MSG_WATCH "Beobachten"
|
||||||
#define MSG_TEMPERATURE "Temperatur"
|
#define MSG_TEMPERATURE "Temperatur"
|
||||||
#define MSG_MOTION "Bewegung"
|
#define MSG_MOTION "Bewegung"
|
||||||
|
#define MSG_CONTRAST "LCD contrast"
|
||||||
#define MSG_STORE_EPROM "EPROM speichern"
|
#define MSG_STORE_EPROM "EPROM speichern"
|
||||||
#define MSG_LOAD_EPROM "EPROM laden"
|
#define MSG_LOAD_EPROM "EPROM laden"
|
||||||
#define MSG_RESTORE_FAILSAFE "Standardkonfig."
|
#define MSG_RESTORE_FAILSAFE "Standardkonfig."
|
||||||
|
@ -674,7 +685,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
#define MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir:"
|
#define MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir:"
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Steprate to high : "
|
#define MSG_STEPPER_TOO_HIGH "Steprate too high : "
|
||||||
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
#define MSG_ENDSTOPS_HIT "endstops hit: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " too long extrusion prevented"
|
||||||
|
@ -685,91 +696,98 @@
|
||||||
#if LANGUAGE_CHOICE == 5
|
#if LANGUAGE_CHOICE == 5
|
||||||
|
|
||||||
// LCD Menu Messages
|
// LCD Menu Messages
|
||||||
#define WELCOME_MSG MACHINE_NAME " Lista."
|
#define WELCOME_MSG MACHINE_NAME "Lista."
|
||||||
#define MSG_SD_INSERTED "Tarjeta SD Colocada"
|
#define MSG_SD_INSERTED "Tarjeta SD Colocada"
|
||||||
#define MSG_SD_REMOVED "Tarjeta SD Retirada"
|
#define MSG_SD_REMOVED "Tarjeta SD Retirada"
|
||||||
#define MSG_MAIN " Menu Principal \003"
|
#define MSG_MAIN "Menu Principal"
|
||||||
#define MSG_AUTOSTART " Autostart"
|
#define MSG_AUTOSTART " Autostart"
|
||||||
#define MSG_DISABLE_STEPPERS " Apagar Motores"
|
#define MSG_DISABLE_STEPPERS "Apagar Motores"
|
||||||
#define MSG_AUTO_HOME " Llevar Ejes al Cero"
|
#define MSG_AUTO_HOME "Llevar al Origen" // "Llevar Ejes al Cero"
|
||||||
#define MSG_SET_ORIGIN " Establecer Cero"
|
#define MSG_SET_ORIGIN "Establecer Cero"
|
||||||
#define MSG_COOLDOWN " Enfriar"
|
#define MSG_PREHEAT_PLA "Precalentar PLA"
|
||||||
#define MSG_EXTRUDE " Extruir"
|
#define MSG_PREHEAT_PLA_SETTINGS "Ajustar temp. PLA"
|
||||||
#define MSG_RETRACT " Retraer"
|
#define MSG_PREHEAT_ABS "Precalentar ABS"
|
||||||
#define MSG_PREHEAT_PLA " Precalentar PLA"
|
#define MSG_PREHEAT_ABS_SETTINGS "Ajustar temp. ABS"
|
||||||
#define MSG_PREHEAT_PLA_SETTINGS " Ajustar temp. PLA"
|
#define MSG_COOLDOWN "Enfriar"
|
||||||
#define MSG_PREHEAT_ABS " Precalentar ABS"
|
#define MSG_EXTRUDE "Extruir"
|
||||||
#define MSG_PREHEAT_ABS_SETTINGS " Ajustar temp. ABS"
|
#define MSG_RETRACT "Retraer"
|
||||||
#define MSG_MOVE_AXIS " Mover Ejes \x7E"
|
#define MSG_MOVE_AXIS "Mover Ejes"
|
||||||
#define MSG_SPEED " Velocidad:"
|
#define MSG_SPEED "Velocidad"
|
||||||
#define MSG_NOZZLE " \002Nozzle:"
|
#define MSG_NOZZLE "Nozzle"
|
||||||
#define MSG_NOZZLE1 " \002Nozzle2:"
|
#define MSG_NOZZLE1 "Nozzle2"
|
||||||
#define MSG_NOZZLE2 " \002Nozzle3:"
|
#define MSG_NOZZLE2 "Nozzle3"
|
||||||
#define MSG_BED " \002Base:"
|
#define MSG_BED "Base"
|
||||||
#define MSG_FAN_SPEED " Ventilador:"
|
#define MSG_FAN_SPEED "Ventilador"
|
||||||
#define MSG_FLOW " Flujo:"
|
#define MSG_FLOW "Flujo"
|
||||||
#define MSG_CONTROL " Control \003"
|
#define MSG_CONTROL "Control"
|
||||||
#define MSG_MIN " \002 Min:"
|
#define MSG_MIN "\002 Min"
|
||||||
#define MSG_MAX " \002 Max:"
|
#define MSG_MAX "\002 Max"
|
||||||
#define MSG_FACTOR " \002 Fact:"
|
#define MSG_FACTOR "\002 Fact"
|
||||||
#define MSG_AUTOTEMP " Autotemp:"
|
#define MSG_AUTOTEMP "Autotemp"
|
||||||
#define MSG_ON "On "
|
#define MSG_ON "On"
|
||||||
#define MSG_OFF "Off"
|
#define MSG_OFF "Off"
|
||||||
#define MSG_PID_P " PID-P: "
|
#define MSG_PID_P "PID-P"
|
||||||
#define MSG_PID_I " PID-I: "
|
#define MSG_PID_I "PID-I"
|
||||||
#define MSG_PID_D " PID-D: "
|
#define MSG_PID_D "PID-D"
|
||||||
#define MSG_PID_C " PID-C: "
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC " Acc:"
|
#define MSG_ACC "Acel"
|
||||||
#define MSG_VXY_JERK " Vxy-jerk: "
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX " Vmax "
|
#define MSG_VMAX "Vmax"
|
||||||
#define MSG_X "x:"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y:"
|
#define MSG_Y "y"
|
||||||
#define MSG_Z "z:"
|
#define MSG_Z "z"
|
||||||
#define MSG_E "e:"
|
#define MSG_E "e"
|
||||||
#define MSG_VMIN " Vmin:"
|
#define MSG_VMIN "Vmin"
|
||||||
#define MSG_VTRAV_MIN " VTrav min:"
|
#define MSG_VTRAV_MIN "VTrav min"
|
||||||
#define MSG_AMAX " Amax "
|
#define MSG_AMAX "Amax"
|
||||||
#define MSG_A_RETRACT " A-retrac.:"
|
#define MSG_A_RETRACT "A-retrac."
|
||||||
#define MSG_XSTEPS " Xpasos/mm:"
|
#define MSG_XSTEPS "X pasos/mm"
|
||||||
#define MSG_YSTEPS " Ypasos/mm:"
|
#define MSG_YSTEPS "Y pasos/mm"
|
||||||
#define MSG_ZSTEPS " Zpasos/mm:"
|
#define MSG_ZSTEPS "Z pasos/mm"
|
||||||
#define MSG_ESTEPS " Epasos/mm:"
|
#define MSG_ESTEPS "E pasos/mm"
|
||||||
#define MSG_MAIN_WIDE " Menu Principal \003"
|
#define MSG_RECTRACT "Retraer"
|
||||||
#define MSG_RECTRACT_WIDE " Retraer \x7E"
|
#define MSG_TEMPERATURE "Temperatura"
|
||||||
#define MSG_TEMPERATURE_WIDE " Temperatura \x7E"
|
#define MSG_MOTION "Movimiento"
|
||||||
#define MSG_TEMPERATURE_RTN " Temperatura \003"
|
#define MSG_STORE_EPROM "Guardar Memoria"
|
||||||
#define MSG_MOTION_WIDE " Movimiento \x7E"
|
#define MSG_LOAD_EPROM "Cargar Memoria"
|
||||||
#define MSG_STORE_EPROM " Guardar Memoria"
|
#define MSG_RESTORE_FAILSAFE "Rest. de emergencia"
|
||||||
#define MSG_LOAD_EPROM " Cargar Memoria"
|
#define MSG_REFRESH "Volver a cargar"
|
||||||
#define MSG_RESTORE_FAILSAFE " Rest. de emergencia"
|
#define MSG_WATCH "Monitorizar"
|
||||||
#define MSG_REFRESH "\004Volver a cargar"
|
#define MSG_PREPARE "Preparar"
|
||||||
#define MSG_WATCH " Monitorizar \003"
|
#define MSG_TUNE "Ajustar"
|
||||||
#define MSG_PREPARE " Preparar \x7E"
|
#define MSG_PAUSE_PRINT "Pausar Impresion"
|
||||||
#define MSG_PREPARE_ALT " Preparar \003"
|
#define MSG_RESUME_PRINT "Reanudar Impresion"
|
||||||
#define MSG_CONTROL_ARROW " Control \x7E"
|
#define MSG_STOP_PRINT "Detener Impresion"
|
||||||
#define MSG_RETRACT_ARROW " Retraer \x7E"
|
#define MSG_CARD_MENU "Menu de SD"
|
||||||
#define MSG_TUNE " Ajustar \x7E"
|
#define MSG_NO_CARD "No hay Tarjeta SD"
|
||||||
#define MSG_PAUSE_PRINT " Pausar Impresion \x7E"
|
|
||||||
#define MSG_RESUME_PRINT " Reanudar Impresion \x7E"
|
|
||||||
#define MSG_STOP_PRINT " Detener Impresion \x7E"
|
|
||||||
#define MSG_CARD_MENU " Menu de SD \x7E"
|
|
||||||
#define MSG_NO_CARD " No hay Tarjeta SD"
|
|
||||||
#define MSG_DWELL "Reposo..."
|
#define MSG_DWELL "Reposo..."
|
||||||
#define MSG_USERWAIT "Esperando Ordenes..."
|
#define MSG_USERWAIT "Esperando Ordenes..."
|
||||||
|
#define MSG_RESUMING "Resumiendo Impresion"
|
||||||
#define MSG_NO_MOVE "Sin movimiento"
|
#define MSG_NO_MOVE "Sin movimiento"
|
||||||
#define MSG_PART_RELEASE "Desacople Parcial"
|
|
||||||
#define MSG_KILLED "PARADA DE EMERGENCIA. "
|
#define MSG_KILLED "PARADA DE EMERGENCIA. "
|
||||||
#define MSG_STOPPED "PARADA. "
|
#define MSG_STOPPED "PARADA."
|
||||||
#define MSG_STEPPER_RELEASED "Desacoplada."
|
#define MSG_CONTROL_RETRACT "Retraer mm"
|
||||||
#define MSG_CONTROL_RETRACT " Retraer mm:"
|
#define MSG_CONTROL_RETRACTF "Retraer F"
|
||||||
#define MSG_CONTROL_RETRACTF " Retraer F:"
|
#define MSG_CONTROL_RETRACT_ZLIFT "Levantar mm"
|
||||||
#define MSG_CONTROL_RETRACT_ZLIFT " Levantar mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER "DesRet +mm"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " DesRet +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVERF "DesRet F"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " DesRet F:"
|
#define MSG_AUTORETRACT "AutoRetr."
|
||||||
#define MSG_AUTORETRACT " AutoRetr.:"
|
|
||||||
#define MSG_FILAMENTCHANGE "Change filament"
|
#define MSG_FILAMENTCHANGE "Change filament"
|
||||||
|
#define MSG_INIT_SDCARD "Iniciando. Tarjeta-SD"
|
||||||
|
#define MSG_CNG_SDCARD "Cambiar Tarjeta-SD"
|
||||||
|
#define MSG_RECTRACT_WIDE "Retraer"
|
||||||
|
#define MSG_TEMPERATURE_WIDE "Temperatura"
|
||||||
|
#define MSG_TEMPERATURE_RTN "Temperatura"
|
||||||
|
#define MSG_MAIN_WIDE "Menu Principal"
|
||||||
|
#define MSG_MOTION_WIDE "Movimiento"
|
||||||
|
#define MSG_PREPARE_ALT "Preparar"
|
||||||
|
#define MSG_CONTROL_ARROW "Control"
|
||||||
|
#define MSG_RETRACT_ARROW "Retraer"
|
||||||
|
#define MSG_PART_RELEASE "Desacople Parcial"
|
||||||
|
#define MSG_STEPPER_RELEASED "Desacoplada."
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
#define MSG_Enqueing "En cola \""
|
#define MSG_Enqueing "En cola \""
|
||||||
|
@ -814,11 +832,11 @@
|
||||||
#define MSG_Y_MIN "y_min: "
|
#define MSG_Y_MIN "y_min: "
|
||||||
#define MSG_Y_MAX "y_max: "
|
#define MSG_Y_MAX "y_max: "
|
||||||
#define MSG_Z_MIN "z_min: "
|
#define MSG_Z_MIN "z_min: "
|
||||||
|
#define MSG_Z_MAX "z_max: "
|
||||||
#define MSG_M119_REPORT "Comprobando fines de carrera."
|
#define MSG_M119_REPORT "Comprobando fines de carrera."
|
||||||
#define MSG_ENDSTOP_HIT "PULSADO"
|
#define MSG_ENDSTOP_HIT "PULSADO"
|
||||||
#define MSG_ENDSTOP_OPEN "abierto"
|
#define MSG_ENDSTOP_OPEN "abierto"
|
||||||
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
#define MSG_HOTEND_OFFSET "Hotend offsets:"
|
||||||
|
|
||||||
#define MSG_SD_CANT_OPEN_SUBDIR "No se pudo abrir la subcarpeta."
|
#define MSG_SD_CANT_OPEN_SUBDIR "No se pudo abrir la subcarpeta."
|
||||||
#define MSG_SD_INIT_FAIL "Fallo al iniciar la SD"
|
#define MSG_SD_INIT_FAIL "Fallo al iniciar la SD"
|
||||||
#define MSG_SD_VOL_INIT_FAIL "Fallo al montar el volumen"
|
#define MSG_SD_VOL_INIT_FAIL "Fallo al montar el volumen"
|
||||||
|
@ -835,7 +853,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "Error al escribir en el archivo"
|
#define MSG_SD_ERR_WRITE_TO_FILE "Error al escribir en el archivo"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "No se puede abrir la carpeta:"
|
#define MSG_SD_CANT_ENTER_SUBDIR "No se puede abrir la carpeta:"
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Steprate demasiado alto : "
|
#define MSG_STEPPER_TOO_HIGH "Steprate demasiado alto : "
|
||||||
#define MSG_ENDSTOPS_HIT "Se ha tocado el fin de carril: "
|
#define MSG_ENDSTOPS_HIT "Se ha tocado el fin de carril: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " extrusion fria evitada"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " extrusion fria evitada"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " extrusion demasiado larga evitada"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " extrusion demasiado larga evitada"
|
||||||
|
@ -881,8 +899,8 @@
|
||||||
#define MSG_PID_C " PID-C: "
|
#define MSG_PID_C " PID-C: "
|
||||||
#define MSG_ACC " Acc:"
|
#define MSG_ACC " Acc:"
|
||||||
#define MSG_VXY_JERK " Vxy-jerk: "
|
#define MSG_VXY_JERK " Vxy-jerk: "
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX " Vmax "
|
#define MSG_VMAX " Vmax "
|
||||||
#define MSG_X "x:"
|
#define MSG_X "x:"
|
||||||
#define MSG_Y "y:"
|
#define MSG_Y "y:"
|
||||||
|
@ -899,6 +917,7 @@
|
||||||
#define MSG_RECTRACT " Откат подачи \x7E"
|
#define MSG_RECTRACT " Откат подачи \x7E"
|
||||||
#define MSG_TEMPERATURE " Температура \x7E"
|
#define MSG_TEMPERATURE " Температура \x7E"
|
||||||
#define MSG_MOTION " Скорости \x7E"
|
#define MSG_MOTION " Скорости \x7E"
|
||||||
|
#define MSG_CONTRAST "LCD contrast"
|
||||||
#define MSG_STORE_EPROM " Сохранить настройки"
|
#define MSG_STORE_EPROM " Сохранить настройки"
|
||||||
#define MSG_LOAD_EPROM " Загрузить настройки"
|
#define MSG_LOAD_EPROM " Загрузить настройки"
|
||||||
#define MSG_RESTORE_FAILSAFE " Сброс настроек "
|
#define MSG_RESTORE_FAILSAFE " Сброс настроек "
|
||||||
|
@ -989,7 +1008,7 @@
|
||||||
#define MSG_SD_NOT_PRINTING "нет SD печати"
|
#define MSG_SD_NOT_PRINTING "нет SD печати"
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "ошибка записи в файл"
|
#define MSG_SD_ERR_WRITE_TO_FILE "ошибка записи в файл"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Не зайти в папку:"
|
#define MSG_SD_CANT_ENTER_SUBDIR "Не зайти в папку:"
|
||||||
#define MSG_STEPPER_TO_HIGH "Частота шагов очень высока : "
|
#define MSG_STEPPER_TOO_HIGH "Частота шагов очень высока : "
|
||||||
#define MSG_ENDSTOPS_HIT "концевик сработал: "
|
#define MSG_ENDSTOPS_HIT "концевик сработал: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " защита холодной экструзии"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " защита холодной экструзии"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " защита превышения длинны экструзии"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " защита превышения длинны экструзии"
|
||||||
|
@ -1000,7 +1019,7 @@
|
||||||
#if LANGUAGE_CHOICE == 7
|
#if LANGUAGE_CHOICE == 7
|
||||||
|
|
||||||
// LCD Menu Messages
|
// LCD Menu Messages
|
||||||
#define WELCOME_MSG MACHINE_NAME " Pronto."
|
#define WELCOME_MSG MACHINE_NAME " Pronta"
|
||||||
#define MSG_SD_INSERTED "SD Card inserita"
|
#define MSG_SD_INSERTED "SD Card inserita"
|
||||||
#define MSG_SD_REMOVED "SD Card rimossa"
|
#define MSG_SD_REMOVED "SD Card rimossa"
|
||||||
#define MSG_MAIN "Menu principale"
|
#define MSG_MAIN "Menu principale"
|
||||||
|
@ -1012,7 +1031,7 @@
|
||||||
#define MSG_PREHEAT_PLA_SETTINGS "Preris. PLA Conf"
|
#define MSG_PREHEAT_PLA_SETTINGS "Preris. PLA Conf"
|
||||||
#define MSG_PREHEAT_ABS "Preriscalda ABS"
|
#define MSG_PREHEAT_ABS "Preriscalda ABS"
|
||||||
#define MSG_PREHEAT_ABS_SETTINGS "Preris. ABS Conf"
|
#define MSG_PREHEAT_ABS_SETTINGS "Preris. ABS Conf"
|
||||||
#define MSG_COOLDOWN "Rafredda"
|
#define MSG_COOLDOWN "Raffredda"
|
||||||
#define MSG_EXTRUDE "Estrudi"
|
#define MSG_EXTRUDE "Estrudi"
|
||||||
#define MSG_RETRACT "Ritrai"
|
#define MSG_RETRACT "Ritrai"
|
||||||
#define MSG_MOVE_AXIS "Muovi Asse"
|
#define MSG_MOVE_AXIS "Muovi Asse"
|
||||||
|
@ -1036,8 +1055,8 @@
|
||||||
#define MSG_PID_C "PID-C"
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC "Accel"
|
#define MSG_ACC "Accel"
|
||||||
#define MSG_VXY_JERK "Vxy-jerk"
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX "Vmax"
|
#define MSG_VMAX "Vmax"
|
||||||
#define MSG_X "x"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y"
|
#define MSG_Y "y"
|
||||||
|
@ -1054,6 +1073,7 @@
|
||||||
#define MSG_RECTRACT "Ritrai"
|
#define MSG_RECTRACT "Ritrai"
|
||||||
#define MSG_TEMPERATURE "Temperatura"
|
#define MSG_TEMPERATURE "Temperatura"
|
||||||
#define MSG_MOTION "Movimento"
|
#define MSG_MOTION "Movimento"
|
||||||
|
#define MSG_CONTRAST "LCD contrast"
|
||||||
#define MSG_STORE_EPROM "Salva in EEPROM"
|
#define MSG_STORE_EPROM "Salva in EEPROM"
|
||||||
#define MSG_LOAD_EPROM "Carica da EEPROM"
|
#define MSG_LOAD_EPROM "Carica da EEPROM"
|
||||||
#define MSG_RESTORE_FAILSAFE "Impostaz. default"
|
#define MSG_RESTORE_FAILSAFE "Impostaz. default"
|
||||||
|
@ -1149,7 +1169,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "Errore nella scrittura su file"
|
#define MSG_SD_ERR_WRITE_TO_FILE "Errore nella scrittura su file"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Impossibile entrare nella sottocartella: "
|
#define MSG_SD_CANT_ENTER_SUBDIR "Impossibile entrare nella sottocartella: "
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Steprate troppo alto: "
|
#define MSG_STEPPER_TOO_HIGH "Steprate troppo alto: "
|
||||||
#define MSG_ENDSTOPS_HIT "Raggiunto il fondo carrello: "
|
#define MSG_ENDSTOPS_HIT "Raggiunto il fondo carrello: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " prevenuta estrusione fredda"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " prevenuta estrusione fredda"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " prevenuta estrusione troppo lunga"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " prevenuta estrusione troppo lunga"
|
||||||
|
@ -1198,8 +1218,8 @@
|
||||||
#define MSG_PID_C " PID-C: "
|
#define MSG_PID_C " PID-C: "
|
||||||
#define MSG_ACC " Acc:"
|
#define MSG_ACC " Acc:"
|
||||||
#define MSG_VXY_JERK " Vxy-jerk: "
|
#define MSG_VXY_JERK " Vxy-jerk: "
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX " Vmax "
|
#define MSG_VMAX " Vmax "
|
||||||
#define MSG_X "x:"
|
#define MSG_X "x:"
|
||||||
#define MSG_Y "y:"
|
#define MSG_Y "y:"
|
||||||
|
@ -1246,8 +1266,8 @@
|
||||||
#define MSG_CONTROL_RETRACT_RECOVER " DesRet +mm:"
|
#define MSG_CONTROL_RETRACT_RECOVER " DesRet +mm:"
|
||||||
#define MSG_CONTROL_RETRACT_RECOVERF " DesRet F:"
|
#define MSG_CONTROL_RETRACT_RECOVERF " DesRet F:"
|
||||||
#define MSG_AUTORETRACT " AutoRetr.:"
|
#define MSG_AUTORETRACT " AutoRetr.:"
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Algo esta errado na estrutura do Menu."
|
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Algo esta errado na estrutura do Menu."
|
||||||
#define MSG_FILAMENTCHANGE "Change filament"
|
#define MSG_FILAMENTCHANGE "Change filament"
|
||||||
|
|
||||||
// Serial Console Messages
|
// Serial Console Messages
|
||||||
|
|
||||||
|
@ -1315,7 +1335,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "Erro ao escrever no arquivo"
|
#define MSG_SD_ERR_WRITE_TO_FILE "Erro ao escrever no arquivo"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Nao pode abrir o sub diretorio:"
|
#define MSG_SD_CANT_ENTER_SUBDIR "Nao pode abrir o sub diretorio:"
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Steprate muito alto : "
|
#define MSG_STEPPER_TOO_HIGH "Steprate muito alto : "
|
||||||
#define MSG_ENDSTOPS_HIT "O ponto final foi tocado: "
|
#define MSG_ENDSTOPS_HIT "O ponto final foi tocado: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " Extrusao a frio evitada"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " Extrusao a frio evitada"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " Extrusao muito larga evitada"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " Extrusao muito larga evitada"
|
||||||
|
@ -1366,8 +1386,8 @@
|
||||||
#define MSG_PID_C "PID-C"
|
#define MSG_PID_C "PID-C"
|
||||||
#define MSG_ACC "Kiihtyv"
|
#define MSG_ACC "Kiihtyv"
|
||||||
#define MSG_VXY_JERK "Vxy-jerk"
|
#define MSG_VXY_JERK "Vxy-jerk"
|
||||||
#define MSG_VZ_JERK "Vz-jerk"
|
#define MSG_VZ_JERK "Vz-jerk"
|
||||||
#define MSG_VE_JERK "Ve-jerk"
|
#define MSG_VE_JERK "Ve-jerk"
|
||||||
#define MSG_VMAX "Vmax "
|
#define MSG_VMAX "Vmax "
|
||||||
#define MSG_X "x"
|
#define MSG_X "x"
|
||||||
#define MSG_Y "y"
|
#define MSG_Y "y"
|
||||||
|
@ -1384,6 +1404,7 @@
|
||||||
#define MSG_RECTRACT "Veda takaisin"
|
#define MSG_RECTRACT "Veda takaisin"
|
||||||
#define MSG_TEMPERATURE "Lampotila"
|
#define MSG_TEMPERATURE "Lampotila"
|
||||||
#define MSG_MOTION "Liike"
|
#define MSG_MOTION "Liike"
|
||||||
|
#define MSG_CONTRAST "LCD contrast"
|
||||||
#define MSG_STORE_EPROM "Tallenna muistiin"
|
#define MSG_STORE_EPROM "Tallenna muistiin"
|
||||||
#define MSG_LOAD_EPROM "Lataa muistista"
|
#define MSG_LOAD_EPROM "Lataa muistista"
|
||||||
#define MSG_RESTORE_FAILSAFE "Palauta oletus"
|
#define MSG_RESTORE_FAILSAFE "Palauta oletus"
|
||||||
|
@ -1476,7 +1497,7 @@
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE "virhe kirjoitettaessa tiedostoon"
|
#define MSG_SD_ERR_WRITE_TO_FILE "virhe kirjoitettaessa tiedostoon"
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR "Alihakemistoon ei voitu siirtya: "
|
#define MSG_SD_CANT_ENTER_SUBDIR "Alihakemistoon ei voitu siirtya: "
|
||||||
|
|
||||||
#define MSG_STEPPER_TO_HIGH "Askellustaajuus liian suuri: "
|
#define MSG_STEPPER_TOO_HIGH "Askellustaajuus liian suuri: "
|
||||||
#define MSG_ENDSTOPS_HIT "paatyrajat aktivoitu: "
|
#define MSG_ENDSTOPS_HIT "paatyrajat aktivoitu: "
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP " kylmana pursotus estetty"
|
#define MSG_ERR_COLD_EXTRUDE_STOP " kylmana pursotus estetty"
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP " liian pitka pursotus estetty"
|
#define MSG_ERR_LONG_EXTRUDE_STOP " liian pitka pursotus estetty"
|
||||||
|
|
494
Marlin/pins.h
494
Marlin/pins.h
|
@ -53,6 +53,7 @@
|
||||||
|
|
||||||
#endif /* 99 */
|
#endif /* 99 */
|
||||||
|
|
||||||
|
|
||||||
/****************************************************************************************
|
/****************************************************************************************
|
||||||
* Gen7 v1.1, v1.2, v1.3 pin assignment
|
* Gen7 v1.1, v1.2, v1.3 pin assignment
|
||||||
*
|
*
|
||||||
|
@ -227,8 +228,8 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//x axis pins
|
//x axis pins
|
||||||
#define X_STEP_PIN 21 //different from stanard GEN7
|
#define X_STEP_PIN 21 // different from standard GEN7
|
||||||
#define X_DIR_PIN 20 //different from stanard GEN7
|
#define X_DIR_PIN 20 // different from standard GEN7
|
||||||
#define X_ENABLE_PIN 24
|
#define X_ENABLE_PIN 24
|
||||||
#define X_STOP_PIN 0
|
#define X_STOP_PIN 0
|
||||||
|
|
||||||
|
@ -297,7 +298,7 @@
|
||||||
* Arduino Mega pin assignment
|
* Arduino Mega pin assignment
|
||||||
*
|
*
|
||||||
****************************************************************************************/
|
****************************************************************************************/
|
||||||
#if MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34
|
#if MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 77
|
||||||
#define KNOWN_BOARD 1
|
#define KNOWN_BOARD 1
|
||||||
|
|
||||||
//////////////////FIX THIS//////////////
|
//////////////////FIX THIS//////////////
|
||||||
|
@ -307,149 +308,229 @@
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
// uncomment one of the following lines for RAMPS v1.3 or v1.0, comment both for v1.2 or 1.1
|
// uncomment one of the following lines for RAMPS v1.3 or v1.0, comment both for v1.2 or 1.1
|
||||||
// #define RAMPS_V_1_3
|
// #define RAMPS_V_1_3
|
||||||
// #define RAMPS_V_1_0
|
// #define RAMPS_V_1_0
|
||||||
|
|
||||||
#if MOTHERBOARD == 33 || MOTHERBOARD == 34
|
|
||||||
|
|
||||||
#define LARGE_FLASH true
|
#if MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 77
|
||||||
|
|
||||||
#define X_STEP_PIN 54
|
#define LARGE_FLASH true
|
||||||
#define X_DIR_PIN 55
|
|
||||||
#define X_ENABLE_PIN 38
|
#if MOTHERBOARD == 77
|
||||||
#define X_MIN_PIN 3
|
#define X_STEP_PIN 54
|
||||||
#define X_MAX_PIN 2
|
#define X_DIR_PIN 55
|
||||||
|
#define X_ENABLE_PIN 38
|
||||||
|
#define X_MIN_PIN 3
|
||||||
|
#define X_MAX_PIN -1 //2 //Max endstops default to disabled "-1", set to commented value to enable.
|
||||||
|
|
||||||
#define Y_STEP_PIN 60
|
#define Y_STEP_PIN 60
|
||||||
#define Y_DIR_PIN 61
|
#define Y_DIR_PIN 61
|
||||||
#define Y_ENABLE_PIN 56
|
#define Y_ENABLE_PIN 56
|
||||||
#define Y_MIN_PIN 14
|
#define Y_MIN_PIN 14
|
||||||
#define Y_MAX_PIN 15
|
#define Y_MAX_PIN -1 //15
|
||||||
|
|
||||||
#define Z_STEP_PIN 46
|
#define Z_STEP_PIN 46
|
||||||
#define Z_DIR_PIN 48
|
#define Z_DIR_PIN 48
|
||||||
#define Z_ENABLE_PIN 62
|
#define Z_ENABLE_PIN 63
|
||||||
#define Z_MIN_PIN 18
|
#define Z_MIN_PIN 18
|
||||||
#define Z_MAX_PIN 19
|
#define Z_MAX_PIN -1
|
||||||
|
|
||||||
#define Z2_STEP_PIN 36
|
#define Z2_STEP_PIN 36
|
||||||
#define Z2_DIR_PIN 34
|
#define Z2_DIR_PIN 34
|
||||||
#define Z2_ENABLE_PIN 30
|
#define Z2_ENABLE_PIN 30
|
||||||
|
|
||||||
#define E0_STEP_PIN 26
|
#define E0_STEP_PIN 26
|
||||||
#define E0_DIR_PIN 28
|
#define E0_DIR_PIN 28
|
||||||
#define E0_ENABLE_PIN 24
|
#define E0_ENABLE_PIN 24
|
||||||
|
|
||||||
#define E1_STEP_PIN 36
|
#define E1_STEP_PIN 36
|
||||||
#define E1_DIR_PIN 34
|
#define E1_DIR_PIN 34
|
||||||
#define E1_ENABLE_PIN 30
|
#define E1_ENABLE_PIN 30
|
||||||
|
|
||||||
#define SDPOWER -1
|
#define SDPOWER -1
|
||||||
#define SDSS 53
|
#define SDSS 25//53
|
||||||
#define LED_PIN 13
|
#define LED_PIN 13
|
||||||
|
|
||||||
#if MOTHERBOARD == 33
|
#define BEEPER 33
|
||||||
#define FAN_PIN 9 // (Sprinter config)
|
|
||||||
#else
|
|
||||||
#define FAN_PIN 4 // IO pin. Buffer needed
|
|
||||||
#endif
|
|
||||||
#define PS_ON_PIN 12
|
|
||||||
|
|
||||||
#if defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
|
#else
|
||||||
#define KILL_PIN 41
|
|
||||||
#else
|
|
||||||
#define KILL_PIN -1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define HEATER_0_PIN 10 // EXTRUDER 1
|
#define X_STEP_PIN 54
|
||||||
#if MOTHERBOARD == 33
|
#define X_DIR_PIN 55
|
||||||
#define HEATER_1_PIN -1
|
#define X_ENABLE_PIN 38
|
||||||
#else
|
#define X_MIN_PIN 3
|
||||||
#define HEATER_1_PIN 9 // EXTRUDER 2 (FAN On Sprinter)
|
#define X_MAX_PIN 2
|
||||||
#endif
|
|
||||||
#define HEATER_2_PIN -1
|
|
||||||
#define TEMP_0_PIN 13 // ANALOG NUMBERING
|
|
||||||
#define TEMP_1_PIN 15 // ANALOG NUMBERING
|
|
||||||
#define TEMP_2_PIN -1 // ANALOG NUMBERING
|
|
||||||
#define HEATER_BED_PIN 8 // BED
|
|
||||||
#define TEMP_BED_PIN 14 // ANALOG NUMBERING
|
|
||||||
|
|
||||||
#ifdef NUM_SERVOS
|
#define Y_STEP_PIN 60
|
||||||
#define SERVO0_PIN 11
|
#define Y_DIR_PIN 61
|
||||||
#if NUM_SERVOS > 1
|
#define Y_ENABLE_PIN 56
|
||||||
#define SERVO1_PIN 6
|
#define Y_MIN_PIN 14
|
||||||
|
#define Y_MAX_PIN 15
|
||||||
|
|
||||||
|
#define Z_STEP_PIN 46
|
||||||
|
#define Z_DIR_PIN 48
|
||||||
|
#define Z_ENABLE_PIN 62
|
||||||
|
#define Z_MIN_PIN 18
|
||||||
|
#define Z_MAX_PIN 19
|
||||||
|
|
||||||
|
#define Z2_STEP_PIN 36
|
||||||
|
#define Z2_DIR_PIN 34
|
||||||
|
#define Z2_ENABLE_PIN 30
|
||||||
|
|
||||||
|
#define E0_STEP_PIN 26
|
||||||
|
#define E0_DIR_PIN 28
|
||||||
|
#define E0_ENABLE_PIN 24
|
||||||
|
|
||||||
|
#define E1_STEP_PIN 36
|
||||||
|
#define E1_DIR_PIN 34
|
||||||
|
#define E1_ENABLE_PIN 30
|
||||||
|
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define SDSS 53
|
||||||
|
#define LED_PIN 13
|
||||||
#endif
|
#endif
|
||||||
#if NUM_SERVOS > 2
|
|
||||||
#define SERVO2_PIN 5
|
#if MOTHERBOARD == 33
|
||||||
|
#define FAN_PIN 9 // (Sprinter config)
|
||||||
|
#else
|
||||||
|
#define FAN_PIN 4 // IO pin. Buffer needed
|
||||||
#endif
|
#endif
|
||||||
#if NUM_SERVOS > 2
|
|
||||||
#define SERVO3_PIN 4
|
#if MOTHERBOARD == 77
|
||||||
|
#define FAN_PIN 8
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef ULTRA_LCD
|
#define PS_ON_PIN 12
|
||||||
|
|
||||||
#ifdef NEWPANEL
|
#if defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
|
||||||
#define LCD_PINS_RS 16
|
#define KILL_PIN 41
|
||||||
#define LCD_PINS_ENABLE 17
|
#else
|
||||||
#define LCD_PINS_D4 23
|
#define KILL_PIN -1
|
||||||
#define LCD_PINS_D5 25
|
#endif
|
||||||
#define LCD_PINS_D6 27
|
|
||||||
#define LCD_PINS_D7 29
|
|
||||||
|
|
||||||
#ifdef REPRAP_DISCOUNT_SMART_CONTROLLER
|
#define HEATER_0_PIN 10 // EXTRUDER 1
|
||||||
#define BEEPER 37
|
#if MOTHERBOARD == 33
|
||||||
|
#define HEATER_1_PIN -1
|
||||||
|
#else
|
||||||
|
#define HEATER_1_PIN 9 // EXTRUDER 2 (FAN On Sprinter)
|
||||||
|
#endif
|
||||||
|
#define HEATER_2_PIN -1
|
||||||
|
|
||||||
#define BTN_EN1 31
|
#if MOTHERBOARD == 77
|
||||||
#define BTN_EN2 33
|
#define HEATER_0_PIN 10
|
||||||
#define BTN_ENC 35
|
#define HEATER_1_PIN 12
|
||||||
|
#define HEATER_2_PIN 6
|
||||||
|
#endif
|
||||||
|
|
||||||
#define SDCARDDETECT 49
|
#define TEMP_0_PIN 13 // ANALOG NUMBERING
|
||||||
#else
|
#define TEMP_1_PIN 15 // ANALOG NUMBERING
|
||||||
//arduino pin which triggers an piezzo beeper
|
#define TEMP_2_PIN -1 // ANALOG NUMBERING
|
||||||
#define BEEPER 33 // Beeper on AUX-4
|
#if MOTHERBOARD == 77
|
||||||
|
#define HEATER_BED_PIN 9 // BED
|
||||||
|
#else
|
||||||
|
#define HEATER_BED_PIN 8 // BED
|
||||||
|
#endif
|
||||||
|
#define TEMP_BED_PIN 14 // ANALOG NUMBERING
|
||||||
|
|
||||||
//buttons are directly attached using AUX-2
|
|
||||||
#ifdef REPRAPWORLD_KEYPAD
|
|
||||||
#define BTN_EN1 64 // encoder
|
|
||||||
#define BTN_EN2 59 // encoder
|
|
||||||
#define BTN_ENC 63 // enter button
|
|
||||||
#define SHIFT_OUT 40 // shift register
|
|
||||||
#define SHIFT_CLK 44 // shift register
|
|
||||||
#define SHIFT_LD 42 // shift register
|
|
||||||
#else
|
|
||||||
#define BTN_EN1 37
|
|
||||||
#define BTN_EN2 35
|
|
||||||
#define BTN_ENC 31 //the click
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef G3D_PANEL
|
|
||||||
#define SDCARDDETECT 49
|
#ifdef NUM_SERVOS
|
||||||
#else
|
#define SERVO0_PIN 11
|
||||||
#define SDCARDDETECT -1 // Ramps does not use this port
|
|
||||||
#endif
|
#if NUM_SERVOS > 1
|
||||||
|
#define SERVO1_PIN 6
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#else //old style panel with shift register
|
#if NUM_SERVOS > 2
|
||||||
//arduino pin witch triggers an piezzo beeper
|
#define SERVO2_PIN 5
|
||||||
#define BEEPER 33 // No Beeper added
|
#endif
|
||||||
|
|
||||||
//buttons are attached to a shift register
|
#if NUM_SERVOS > 3
|
||||||
// Not wired this yet
|
#define SERVO3_PIN 4
|
||||||
//#define SHIFT_CLK 38
|
#endif
|
||||||
//#define SHIFT_LD 42
|
#endif
|
||||||
//#define SHIFT_OUT 40
|
|
||||||
//#define SHIFT_EN 17
|
|
||||||
|
|
||||||
#define LCD_PINS_RS 16
|
#ifdef ULTRA_LCD
|
||||||
#define LCD_PINS_ENABLE 17
|
|
||||||
#define LCD_PINS_D4 23
|
#ifdef NEWPANEL
|
||||||
#define LCD_PINS_D5 25
|
#define LCD_PINS_RS 16
|
||||||
#define LCD_PINS_D6 27
|
#define LCD_PINS_ENABLE 17
|
||||||
#define LCD_PINS_D7 29
|
#define LCD_PINS_D4 23
|
||||||
#endif
|
#define LCD_PINS_D5 25
|
||||||
#endif //ULTRA_LCD
|
#define LCD_PINS_D6 27
|
||||||
|
#define LCD_PINS_D7 29
|
||||||
|
|
||||||
|
#ifdef REPRAP_DISCOUNT_SMART_CONTROLLER
|
||||||
|
#define BEEPER 37
|
||||||
|
|
||||||
|
#define BTN_EN1 31
|
||||||
|
#define BTN_EN2 33
|
||||||
|
#define BTN_ENC 35
|
||||||
|
|
||||||
|
#define SDCARDDETECT 49
|
||||||
|
#else
|
||||||
|
//arduino pin which triggers an piezzo beeper
|
||||||
|
#define BEEPER 33 // Beeper on AUX-4
|
||||||
|
|
||||||
|
//buttons are directly attached using AUX-2
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
#define BTN_EN1 64 // encoder
|
||||||
|
#define BTN_EN2 59 // encoder
|
||||||
|
#define BTN_ENC 63 // enter button
|
||||||
|
#define SHIFT_OUT 40 // shift register
|
||||||
|
#define SHIFT_CLK 44 // shift register
|
||||||
|
#define SHIFT_LD 42 // shift register
|
||||||
|
#else
|
||||||
|
#define BTN_EN1 37
|
||||||
|
#define BTN_EN2 35
|
||||||
|
#define BTN_ENC 31 //the click
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef G3D_PANEL
|
||||||
|
#define SDCARDDETECT 49
|
||||||
|
#else
|
||||||
|
#define SDCARDDETECT -1 // Ramps does not use this port
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if MOTHERBOARD == 77
|
||||||
|
#define BEEPER -1
|
||||||
|
|
||||||
|
#define LCD_PINS_RS 27
|
||||||
|
#define LCD_PINS_ENABLE 29
|
||||||
|
#define LCD_PINS_D4 37
|
||||||
|
#define LCD_PINS_D5 35
|
||||||
|
#define LCD_PINS_D6 33
|
||||||
|
#define LCD_PINS_D7 31
|
||||||
|
|
||||||
|
//buttons
|
||||||
|
#define BTN_EN1 16
|
||||||
|
#define BTN_EN2 17
|
||||||
|
#define BTN_ENC 23 //the click
|
||||||
|
|
||||||
|
#endif
|
||||||
|
#else //old style panel with shift register
|
||||||
|
//arduino pin witch triggers an piezzo beeper
|
||||||
|
#define BEEPER 33 //No Beeper added
|
||||||
|
|
||||||
|
//buttons are attached to a shift register
|
||||||
|
// Not wired this yet
|
||||||
|
//#define SHIFT_CLK 38
|
||||||
|
//#define SHIFT_LD 42
|
||||||
|
//#define SHIFT_OUT 40
|
||||||
|
//#define SHIFT_EN 17
|
||||||
|
|
||||||
|
#define LCD_PINS_RS 16
|
||||||
|
#define LCD_PINS_ENABLE 17
|
||||||
|
#define LCD_PINS_D4 23
|
||||||
|
#define LCD_PINS_D5 25
|
||||||
|
#define LCD_PINS_D6 27
|
||||||
|
#define LCD_PINS_D7 29
|
||||||
|
#endif
|
||||||
|
#endif //ULTRA_LCD
|
||||||
|
|
||||||
#else // RAMPS_V_1_1 or RAMPS_V_1_2 as default (MOTHERBOARD == 3)
|
#else // RAMPS_V_1_1 or RAMPS_V_1_2 as default (MOTHERBOARD == 3)
|
||||||
|
|
||||||
|
@ -493,15 +574,16 @@
|
||||||
#define HEATER_1_PIN -1
|
#define HEATER_1_PIN -1
|
||||||
#define HEATER_2_PIN -1
|
#define HEATER_2_PIN -1
|
||||||
#define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
|
#define TEMP_0_PIN 2 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
|
||||||
#define TEMP_1_PIN -1
|
#define TEMP_1_PIN -1
|
||||||
#define TEMP_2_PIN -1
|
#define TEMP_2_PIN -1
|
||||||
#define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
|
#define TEMP_BED_PIN 1 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
|
||||||
#endif// MOTHERBOARD == 33 || MOTHERBOARD == 34
|
|
||||||
|
|
||||||
// SPI for Max6675 Thermocouple
|
#endif // MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 77
|
||||||
|
|
||||||
|
// SPI for Max6675 Thermocouple
|
||||||
|
|
||||||
#ifndef SDSUPPORT
|
#ifndef SDSUPPORT
|
||||||
// these pins are defined in the SD library if building with SD support
|
// these pins are defined in the SD library if building with SD support
|
||||||
#define MAX_SCK_PIN 52
|
#define MAX_SCK_PIN 52
|
||||||
#define MAX_MISO_PIN 50
|
#define MAX_MISO_PIN 50
|
||||||
#define MAX_MOSI_PIN 51
|
#define MAX_MOSI_PIN 51
|
||||||
|
@ -510,7 +592,9 @@
|
||||||
#define MAX6675_SS 49
|
#define MAX6675_SS 49
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif//MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34
|
#endif //MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34 || MOTHERBOARD == 77
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/****************************************************************************************
|
/****************************************************************************************
|
||||||
* Duemilanove w/ ATMega328P pin assignment
|
* Duemilanove w/ ATMega328P pin assignment
|
||||||
|
@ -560,6 +644,131 @@
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/****************************************************************************************
|
||||||
|
* Elefu RA Board Pin Assignments
|
||||||
|
*
|
||||||
|
****************************************************************************************/
|
||||||
|
#if MOTHERBOARD == 21
|
||||||
|
#define KNOWN_BOARD 1
|
||||||
|
|
||||||
|
#ifndef __AVR_ATmega2560__
|
||||||
|
#error Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
#define X_STEP_PIN 49
|
||||||
|
#define X_DIR_PIN 13
|
||||||
|
#define X_ENABLE_PIN 48
|
||||||
|
#define X_MIN_PIN 35
|
||||||
|
#define X_MAX_PIN -1 //34
|
||||||
|
|
||||||
|
#define Y_STEP_PIN 11
|
||||||
|
#define Y_DIR_PIN 9
|
||||||
|
#define Y_ENABLE_PIN 12
|
||||||
|
#define Y_MIN_PIN 33
|
||||||
|
#define Y_MAX_PIN -1 //32
|
||||||
|
|
||||||
|
#define Z_STEP_PIN 7
|
||||||
|
#define Z_DIR_PIN 6
|
||||||
|
#define Z_ENABLE_PIN 8
|
||||||
|
#define Z_MIN_PIN 31
|
||||||
|
#define Z_MAX_PIN -1 //30
|
||||||
|
|
||||||
|
#define E2_STEP_PIN 43
|
||||||
|
#define E2_DIR_PIN 47
|
||||||
|
#define E2_ENABLE_PIN 42
|
||||||
|
|
||||||
|
#define E1_STEP_PIN 18
|
||||||
|
#define E1_DIR_PIN 19
|
||||||
|
#define E1_ENABLE_PIN 38
|
||||||
|
|
||||||
|
#define E0_STEP_PIN 40
|
||||||
|
#define E0_DIR_PIN 41
|
||||||
|
#define E0_ENABLE_PIN 37
|
||||||
|
|
||||||
|
#define SDPOWER -1
|
||||||
|
#define LED_PIN -1 //Use +12V Aux port for LED Ring
|
||||||
|
|
||||||
|
#define FAN_PIN 16 //5V PWM
|
||||||
|
|
||||||
|
#define PS_ON_PIN 10 //Set to -1 if using a manual switch on the PWRSW Connector
|
||||||
|
#define SLEEP_WAKE_PIN 26 //This feature still needs work
|
||||||
|
|
||||||
|
#define HEATER_0_PIN 45 //12V PWM1
|
||||||
|
#define HEATER_1_PIN 46 //12V PWM2
|
||||||
|
#define HEATER_2_PIN 17 //12V PWM3
|
||||||
|
#define HEATER_BED_PIN 44 //DOUBLE 12V PWM
|
||||||
|
#define TEMP_0_PIN 3 //ANALOG NUMBERING
|
||||||
|
#define TEMP_1_PIN 2 //ANALOG NUMBERING
|
||||||
|
#define TEMP_2_PIN 1 //ANALOG NUMBERING
|
||||||
|
#define TEMP_BED_PIN 0 //ANALOG NUMBERING
|
||||||
|
|
||||||
|
#define BEEPER 36
|
||||||
|
|
||||||
|
#define KILL_PIN -1
|
||||||
|
|
||||||
|
// 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 29
|
||||||
|
|
||||||
|
#ifdef RA_CONTROL_PANEL
|
||||||
|
|
||||||
|
#define SDSS 53
|
||||||
|
#define SDCARDDETECT 28
|
||||||
|
|
||||||
|
#define BTN_EN1 14
|
||||||
|
#define BTN_EN2 39
|
||||||
|
#define BTN_ENC 15 //the click
|
||||||
|
|
||||||
|
#define BLEN_C 2
|
||||||
|
#define BLEN_B 1
|
||||||
|
#define BLEN_A 0
|
||||||
|
|
||||||
|
//encoder rotation values
|
||||||
|
#define encrot0 0
|
||||||
|
#define encrot1 2
|
||||||
|
#define encrot2 3
|
||||||
|
#define encrot3 1
|
||||||
|
|
||||||
|
#endif //RA_CONTROL_PANEL
|
||||||
|
|
||||||
|
#ifdef RA_DISCO
|
||||||
|
//variables for which pins the TLC5947 is using
|
||||||
|
#define TLC_CLOCK_PIN 25
|
||||||
|
#define TLC_BLANK_PIN 23
|
||||||
|
#define TLC_XLAT_PIN 22
|
||||||
|
#define TLC_DATA_PIN 24
|
||||||
|
|
||||||
|
//We also need to define pin to port number mapping for the 2560 to match the pins listed above. If you change the TLC pins, update this as well per the 2560 datasheet!
|
||||||
|
//This currently only works with the RA Board.
|
||||||
|
#define TLC_CLOCK_BIT 3 //bit 3 on port A
|
||||||
|
#define TLC_CLOCK_PORT &PORTA //bit 3 on port A
|
||||||
|
|
||||||
|
#define TLC_BLANK_BIT 1 //bit 1 on port A
|
||||||
|
#define TLC_BLANK_PORT &PORTA //bit 1 on port A
|
||||||
|
|
||||||
|
#define TLC_DATA_BIT 2 //bit 2 on port A
|
||||||
|
#define TLC_DATA_PORT &PORTA //bit 2 on port A
|
||||||
|
|
||||||
|
#define TLC_XLAT_BIT 0 //bit 0 on port A
|
||||||
|
#define TLC_XLAT_PORT &PORTA //bit 0 on port A
|
||||||
|
|
||||||
|
//change this to match your situation. Lots of TLCs takes up the arduino SRAM very quickly, so be careful
|
||||||
|
//Leave it at at least 1 if you have enabled RA_LIGHTING
|
||||||
|
//The number of TLC5947 boards chained together for use with the animation, additional ones will repeat the animation on them, but are not individually addressable and mimic those before them. You can leave the default at 2 even if you only have 1 TLC5947 module.
|
||||||
|
#define NUM_TLCS 2
|
||||||
|
|
||||||
|
//These TRANS_ARRAY values let you change the order the LEDs on the lighting modules will animate for chase functions.
|
||||||
|
//Modify them according to your specific situation.
|
||||||
|
//NOTE: the array should be 8 long for every TLC you have. These defaults assume (2) TLCs.
|
||||||
|
#define TRANS_ARRAY {0, 1, 2, 3, 4, 5, 6, 7, 15, 14, 13, 12, 11, 10, 9, 8} //forwards
|
||||||
|
//#define TRANS_ARRAY {7, 6, 5, 4, 3, 2, 1, 0, 8, 9, 10, 11, 12, 13, 14, 15} //backwards
|
||||||
|
#endif //RA_LIGHTING
|
||||||
|
|
||||||
|
|
||||||
|
#endif /* Ra Board */
|
||||||
|
|
||||||
|
|
||||||
/****************************************************************************************
|
/****************************************************************************************
|
||||||
* Gen6 pin assignment
|
* Gen6 pin assignment
|
||||||
*
|
*
|
||||||
|
@ -634,10 +843,13 @@
|
||||||
#if MOTHERBOARD == 64
|
#if MOTHERBOARD == 64
|
||||||
#define STB
|
#define STB
|
||||||
#endif
|
#endif
|
||||||
#if MOTHERBOARD == 63
|
#if MOTHERBOARD == 63 || MOTHERBOARD == 66
|
||||||
#define MELZI
|
#define MELZI
|
||||||
#endif
|
#endif
|
||||||
#if MOTHERBOARD == 62 || MOTHERBOARD == 63 || MOTHERBOARD == 64
|
#if MOTHERBOARD == 65
|
||||||
|
#define AZTEEG_X1
|
||||||
|
#endif
|
||||||
|
#if MOTHERBOARD == 62 || MOTHERBOARD == 63 || MOTHERBOARD == 64 || MOTHERBOARD == 65 || MOTHERBOARD == 66
|
||||||
#undef MOTHERBOARD
|
#undef MOTHERBOARD
|
||||||
#define MOTHERBOARD 6
|
#define MOTHERBOARD 6
|
||||||
#define SANGUINOLOLU_V_1_2
|
#define SANGUINOLOLU_V_1_2
|
||||||
|
@ -678,6 +890,12 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef STB
|
#ifdef STB
|
||||||
|
#define FAN_PIN 4
|
||||||
|
// Uncomment this if you have the first generation (V1.10) of STBs board
|
||||||
|
#define LCD_PIN_BL 17 // LCD backlight LED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef AZTEEG_X1
|
||||||
#define FAN_PIN 4
|
#define FAN_PIN 4
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -759,6 +977,27 @@
|
||||||
#endif //Newpanel
|
#endif //Newpanel
|
||||||
#endif //Ultipanel
|
#endif //Ultipanel
|
||||||
|
|
||||||
|
#ifdef MAKRPANEL
|
||||||
|
#define BEEPER 29
|
||||||
|
// Pins for DOGM SPI LCD Support
|
||||||
|
#define DOGLCD_A0 30
|
||||||
|
#define DOGLCD_CS 17
|
||||||
|
#define LCD_PIN_BL 28 // backlight LED on PA3
|
||||||
|
// GLCD features
|
||||||
|
#define LCD_CONTRAST 1
|
||||||
|
// Uncomment screen orientation
|
||||||
|
#define LCD_SCREEN_ROT_0
|
||||||
|
// #define LCD_SCREEN_ROT_90
|
||||||
|
// #define LCD_SCREEN_ROT_180
|
||||||
|
// #define LCD_SCREEN_ROT_270
|
||||||
|
//The encoder and click button
|
||||||
|
#define BTN_EN1 11
|
||||||
|
#define BTN_EN2 10
|
||||||
|
#define BTN_ENC 16 //the click switch
|
||||||
|
//not connected to a pin
|
||||||
|
#define SDCARDDETECT -1
|
||||||
|
#endif //Makrpanel
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
@ -1831,8 +2070,15 @@
|
||||||
#define Z_MAX_PIN -1
|
#define Z_MAX_PIN -1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef DISABLE_MIN_ENDSTOPS
|
||||||
|
#define X_MIN_PIN -1
|
||||||
|
#define Y_MIN_PIN -1
|
||||||
|
#define Z_MIN_PIN -1
|
||||||
|
#endif
|
||||||
|
|
||||||
#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, PS_ON_PIN, \
|
#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, PS_ON_PIN, \
|
||||||
HEATER_BED_PIN, FAN_PIN, \
|
HEATER_BED_PIN, FAN_PIN, \
|
||||||
_E0_PINS _E1_PINS _E2_PINS \
|
_E0_PINS _E1_PINS _E2_PINS \
|
||||||
analogInputToDigitalPin(TEMP_0_PIN), analogInputToDigitalPin(TEMP_1_PIN), analogInputToDigitalPin(TEMP_2_PIN), analogInputToDigitalPin(TEMP_BED_PIN) }
|
analogInputToDigitalPin(TEMP_0_PIN), analogInputToDigitalPin(TEMP_1_PIN), analogInputToDigitalPin(TEMP_2_PIN), analogInputToDigitalPin(TEMP_BED_PIN) }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -98,7 +98,7 @@ volatile unsigned char block_buffer_tail; // Index of the block to pro
|
||||||
//=============================private variables ============================
|
//=============================private variables ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
bool allow_cold_extrude=false;
|
float extrude_min_temp=EXTRUDE_MINTEMP;
|
||||||
#endif
|
#endif
|
||||||
#ifdef XY_FREQUENCY_LIMIT
|
#ifdef XY_FREQUENCY_LIMIT
|
||||||
#define MAX_FREQ_TIME (1000000.0/XY_FREQUENCY_LIMIT)
|
#define MAX_FREQ_TIME (1000000.0/XY_FREQUENCY_LIMIT)
|
||||||
|
@ -473,22 +473,24 @@ void check_axes_activity()
|
||||||
disable_e2();
|
disable_e2();
|
||||||
}
|
}
|
||||||
#if defined(FAN_PIN) && FAN_PIN > -1
|
#if defined(FAN_PIN) && FAN_PIN > -1
|
||||||
#ifndef FAN_SOFT_PWM
|
#ifdef FAN_KICKSTART_TIME
|
||||||
#ifdef FAN_KICKSTART_TIME
|
static unsigned long fan_kick_end;
|
||||||
static unsigned long fan_kick_end;
|
if (tail_fan_speed) {
|
||||||
if (tail_fan_speed) {
|
if (fan_kick_end == 0) {
|
||||||
if (fan_kick_end == 0) {
|
// Just starting up fan - run at full power.
|
||||||
// Just starting up fan - run at full power.
|
fan_kick_end = millis() + FAN_KICKSTART_TIME;
|
||||||
fan_kick_end = millis() + FAN_KICKSTART_TIME;
|
tail_fan_speed = 255;
|
||||||
tail_fan_speed = 255;
|
} else if (fan_kick_end > millis())
|
||||||
} else if (fan_kick_end > millis())
|
// Fan still spinning up.
|
||||||
// Fan still spinning up.
|
tail_fan_speed = 255;
|
||||||
tail_fan_speed = 255;
|
} else {
|
||||||
} else {
|
fan_kick_end = 0;
|
||||||
fan_kick_end = 0;
|
}
|
||||||
}
|
#endif//FAN_KICKSTART_TIME
|
||||||
#endif//FAN_KICKSTART_TIME
|
#ifdef FAN_SOFT_PWM
|
||||||
analogWrite(FAN_PIN,tail_fan_speed);
|
fanSpeedSoftPwm = tail_fan_speed;
|
||||||
|
#else
|
||||||
|
analogWrite(FAN_PIN,tail_fan_speed);
|
||||||
#endif//!FAN_SOFT_PWM
|
#endif//!FAN_SOFT_PWM
|
||||||
#endif//FAN_PIN > -1
|
#endif//FAN_PIN > -1
|
||||||
#ifdef AUTOTEMP
|
#ifdef AUTOTEMP
|
||||||
|
@ -537,7 +539,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
if(target[E_AXIS]!=position[E_AXIS])
|
if(target[E_AXIS]!=position[E_AXIS])
|
||||||
{
|
{
|
||||||
if(degHotend(active_extruder)<EXTRUDE_MINTEMP && !allow_cold_extrude)
|
if(degHotend(active_extruder)<extrude_min_temp)
|
||||||
{
|
{
|
||||||
position[E_AXIS]=target[E_AXIS]; //behave as if the move really took place, but ignore E part
|
position[E_AXIS]=target[E_AXIS]; //behave as if the move really took place, but ignore E part
|
||||||
SERIAL_ECHO_START;
|
SERIAL_ECHO_START;
|
||||||
|
@ -562,8 +564,16 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
block->busy = false;
|
block->busy = false;
|
||||||
|
|
||||||
// Number of steps for each axis
|
// Number of steps for each axis
|
||||||
block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
|
#ifndef COREXY
|
||||||
block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
|
// default non-h-bot planning
|
||||||
|
block->steps_x = labs(target[X_AXIS]-position[X_AXIS]);
|
||||||
|
block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
|
||||||
|
#else
|
||||||
|
// corexy planning
|
||||||
|
// these equations follow the form of the dA and dB equations on http://www.corexy.com/theory.html
|
||||||
|
block->steps_x = labs((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]));
|
||||||
|
block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]));
|
||||||
|
#endif
|
||||||
block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
|
block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
|
||||||
block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
|
block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
|
||||||
block->steps_e *= extrudemultiply;
|
block->steps_e *= extrudemultiply;
|
||||||
|
@ -584,6 +594,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
|
|
||||||
// Compute direction bits for this block
|
// Compute direction bits for this block
|
||||||
block->direction_bits = 0;
|
block->direction_bits = 0;
|
||||||
|
#ifndef COREXY
|
||||||
if (target[X_AXIS] < position[X_AXIS])
|
if (target[X_AXIS] < position[X_AXIS])
|
||||||
{
|
{
|
||||||
block->direction_bits |= (1<<X_AXIS);
|
block->direction_bits |= (1<<X_AXIS);
|
||||||
|
@ -592,6 +603,16 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
{
|
{
|
||||||
block->direction_bits |= (1<<Y_AXIS);
|
block->direction_bits |= (1<<Y_AXIS);
|
||||||
}
|
}
|
||||||
|
#else
|
||||||
|
if ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]) < 0)
|
||||||
|
{
|
||||||
|
block->direction_bits |= (1<<X_AXIS);
|
||||||
|
}
|
||||||
|
if ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]) < 0)
|
||||||
|
{
|
||||||
|
block->direction_bits |= (1<<Y_AXIS);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
if (target[Z_AXIS] < position[Z_AXIS])
|
if (target[Z_AXIS] < position[Z_AXIS])
|
||||||
{
|
{
|
||||||
block->direction_bits |= (1<<Z_AXIS);
|
block->direction_bits |= (1<<Z_AXIS);
|
||||||
|
@ -636,8 +657,13 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
}
|
}
|
||||||
|
|
||||||
float delta_mm[4];
|
float delta_mm[4];
|
||||||
delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
|
#ifndef COREXY
|
||||||
delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
|
delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
|
||||||
|
delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
|
||||||
|
#else
|
||||||
|
delta_mm[X_AXIS] = ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]))/axis_steps_per_unit[X_AXIS];
|
||||||
|
delta_mm[Y_AXIS] = ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]))/axis_steps_per_unit[Y_AXIS];
|
||||||
|
#endif
|
||||||
delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
|
delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
|
||||||
delta_mm[E_AXIS] = ((target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS])*extrudemultiply/100.0;
|
delta_mm[E_AXIS] = ((target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS])*extrudemultiply/100.0;
|
||||||
if ( block->steps_x <=dropsegments && block->steps_y <=dropsegments && block->steps_z <=dropsegments )
|
if ( block->steps_x <=dropsegments && block->steps_y <=dropsegments && block->steps_z <=dropsegments )
|
||||||
|
@ -757,7 +783,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
|
||||||
block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
|
block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
|
||||||
}
|
}
|
||||||
block->acceleration = block->acceleration_st / steps_per_mm;
|
block->acceleration = block->acceleration_st / steps_per_mm;
|
||||||
block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608);
|
block->acceleration_rate = (long)((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));
|
||||||
|
|
||||||
#if 0 // Use old jerk for now
|
#if 0 // Use old jerk for now
|
||||||
// Compute path unit vector
|
// Compute path unit vector
|
||||||
|
@ -918,12 +944,12 @@ uint8_t movesplanned()
|
||||||
return (block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
|
return (block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void allow_cold_extrudes(bool allow)
|
|
||||||
{
|
|
||||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
allow_cold_extrude=allow;
|
void set_extrude_min_temp(float temp)
|
||||||
#endif
|
{
|
||||||
|
extrude_min_temp=temp;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// Calculate the steps/s^2 acceleration rates, based on the mm/s^s
|
// Calculate the steps/s^2 acceleration rates, based on the mm/s^s
|
||||||
void reset_acceleration_rates()
|
void reset_acceleration_rates()
|
||||||
|
|
|
@ -139,7 +139,9 @@ FORCE_INLINE bool blocks_queued()
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void allow_cold_extrudes(bool allow);
|
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||||
|
void set_extrude_min_temp(float temp);
|
||||||
|
#endif
|
||||||
|
|
||||||
void reset_acceleration_rates();
|
void reset_acceleration_rates();
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -272,7 +272,7 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
|
||||||
timer = (unsigned short)pgm_read_word_near(table_address);
|
timer = (unsigned short)pgm_read_word_near(table_address);
|
||||||
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
|
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
|
||||||
}
|
}
|
||||||
if(timer < 100) { timer = 100; MYSERIAL.print(MSG_STEPPER_TO_HIGH); MYSERIAL.println(step_rate); }//(20kHz this should never happen)
|
if(timer < 100) { timer = 100; MYSERIAL.print(MSG_STEPPER_TOO_HIGH); MYSERIAL.println(step_rate); }//(20kHz this should never happen)
|
||||||
return timer;
|
return timer;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -345,50 +345,86 @@ ISR(TIMER1_COMPA_vect)
|
||||||
// Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
|
// Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
|
||||||
out_bits = current_block->direction_bits;
|
out_bits = current_block->direction_bits;
|
||||||
|
|
||||||
// Set direction en check limit switches
|
|
||||||
if ((out_bits & (1<<X_AXIS)) != 0) { // stepping along -X axis
|
// Set the direction bits (X_AXIS=A_AXIS and Y_AXIS=B_AXIS for COREXY)
|
||||||
#if !defined COREXY //NOT COREXY
|
if((out_bits & (1<<X_AXIS))!=0){
|
||||||
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
if (active_extruder != 0)
|
||||||
|
WRITE(X2_DIR_PIN,INVERT_X_DIR);
|
||||||
|
else
|
||||||
|
#endif
|
||||||
WRITE(X_DIR_PIN, INVERT_X_DIR);
|
WRITE(X_DIR_PIN, INVERT_X_DIR);
|
||||||
#endif
|
|
||||||
count_direction[X_AXIS]=-1;
|
count_direction[X_AXIS]=-1;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
if (active_extruder != 0)
|
||||||
|
WRITE(X2_DIR_PIN,!INVERT_X_DIR);
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
WRITE(X_DIR_PIN, !INVERT_X_DIR);
|
||||||
|
count_direction[X_AXIS]=1;
|
||||||
|
}
|
||||||
|
if((out_bits & (1<<Y_AXIS))!=0){
|
||||||
|
WRITE(Y_DIR_PIN, INVERT_Y_DIR);
|
||||||
|
count_direction[Y_AXIS]=-1;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
|
||||||
|
count_direction[Y_AXIS]=1;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Set direction en check limit switches
|
||||||
|
#ifndef COREXY
|
||||||
|
if ((out_bits & (1<<X_AXIS)) != 0) { // stepping along -X axis
|
||||||
|
#else
|
||||||
|
if ((((out_bits & (1<<X_AXIS)) != 0)&&(out_bits & (1<<Y_AXIS)) != 0)) { //-X occurs for -A and -B
|
||||||
|
#endif
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
#ifdef DUAL_X_CARRIAGE
|
||||||
bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
|
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
|
||||||
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
|
if ((active_extruder == 0 && X_HOME_DIR == -1) || (active_extruder != 0 && X2_HOME_DIR == -1))
|
||||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
#endif
|
||||||
endstop_x_hit=true;
|
{
|
||||||
step_events_completed = current_block->step_event_count;
|
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
||||||
}
|
bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
|
||||||
old_x_min_endstop = x_min_endstop;
|
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
|
||||||
#endif
|
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||||
|
endstop_x_hit=true;
|
||||||
|
step_events_completed = current_block->step_event_count;
|
||||||
|
}
|
||||||
|
old_x_min_endstop = x_min_endstop;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else { // +direction
|
else { // +direction
|
||||||
#if !defined COREXY //NOT COREXY
|
|
||||||
WRITE(X_DIR_PIN,!INVERT_X_DIR);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
count_direction[X_AXIS]=1;
|
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
|
#ifdef DUAL_X_CARRIAGE
|
||||||
bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
|
// with 2 x-carriages, endstops are only checked in the homing direction for the active extruder
|
||||||
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
|
if ((active_extruder == 0 && X_HOME_DIR == 1) || (active_extruder != 0 && X2_HOME_DIR == 1))
|
||||||
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
#endif
|
||||||
endstop_x_hit=true;
|
{
|
||||||
step_events_completed = current_block->step_event_count;
|
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
|
||||||
}
|
bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
|
||||||
old_x_max_endstop = x_max_endstop;
|
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
|
||||||
#endif
|
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
|
||||||
|
endstop_x_hit=true;
|
||||||
|
step_events_completed = current_block->step_event_count;
|
||||||
|
}
|
||||||
|
old_x_max_endstop = x_max_endstop;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifndef COREXY
|
||||||
if ((out_bits & (1<<Y_AXIS)) != 0) { // -direction
|
if ((out_bits & (1<<Y_AXIS)) != 0) { // -direction
|
||||||
#if !defined COREXY //NOT COREXY
|
#else
|
||||||
WRITE(Y_DIR_PIN,INVERT_Y_DIR);
|
if ((((out_bits & (1<<X_AXIS)) != 0)&&(out_bits & (1<<Y_AXIS)) == 0)) { // -Y occurs for -A and +B
|
||||||
#endif
|
#endif
|
||||||
count_direction[Y_AXIS]=-1;
|
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
|
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
|
||||||
|
@ -403,10 +439,6 @@ ISR(TIMER1_COMPA_vect)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else { // +direction
|
else { // +direction
|
||||||
#if !defined COREXY //NOT COREXY
|
|
||||||
WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
|
|
||||||
#endif
|
|
||||||
count_direction[Y_AXIS]=1;
|
|
||||||
CHECK_ENDSTOPS
|
CHECK_ENDSTOPS
|
||||||
{
|
{
|
||||||
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
|
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
|
||||||
|
@ -420,28 +452,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
#ifdef COREXY //coreXY kinematics defined
|
|
||||||
if((current_block->steps_x >= current_block->steps_y)&&((out_bits & (1<<X_AXIS)) == 0)){ //+X is major axis
|
|
||||||
WRITE(X_DIR_PIN, !INVERT_X_DIR);
|
|
||||||
WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
|
|
||||||
}
|
|
||||||
if((current_block->steps_x >= current_block->steps_y)&&((out_bits & (1<<X_AXIS)) != 0)){ //-X is major axis
|
|
||||||
WRITE(X_DIR_PIN, INVERT_X_DIR);
|
|
||||||
WRITE(Y_DIR_PIN, INVERT_Y_DIR);
|
|
||||||
}
|
|
||||||
if((current_block->steps_y > current_block->steps_x)&&((out_bits & (1<<Y_AXIS)) == 0)){ //+Y is major axis
|
|
||||||
WRITE(X_DIR_PIN, !INVERT_X_DIR);
|
|
||||||
WRITE(Y_DIR_PIN, INVERT_Y_DIR);
|
|
||||||
}
|
|
||||||
if((current_block->steps_y > current_block->steps_x)&&((out_bits & (1<<Y_AXIS)) != 0)){ //-Y is major axis
|
|
||||||
WRITE(X_DIR_PIN, INVERT_X_DIR);
|
|
||||||
WRITE(Y_DIR_PIN, !INVERT_Y_DIR);
|
|
||||||
}
|
|
||||||
#endif //coreXY
|
|
||||||
|
|
||||||
|
|
||||||
if ((out_bits & (1<<Z_AXIS)) != 0) { // -direction
|
if ((out_bits & (1<<Z_AXIS)) != 0) { // -direction
|
||||||
WRITE(Z_DIR_PIN,INVERT_Z_DIR);
|
WRITE(Z_DIR_PIN,INVERT_Z_DIR);
|
||||||
|
|
||||||
|
@ -516,13 +527,22 @@ ISR(TIMER1_COMPA_vect)
|
||||||
}
|
}
|
||||||
#endif //ADVANCE
|
#endif //ADVANCE
|
||||||
|
|
||||||
#if !defined COREXY
|
|
||||||
counter_x += current_block->steps_x;
|
counter_x += current_block->steps_x;
|
||||||
if (counter_x > 0) {
|
if (counter_x > 0) {
|
||||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
if (active_extruder != 0)
|
||||||
|
WRITE(X2_STEP_PIN,!INVERT_X_STEP_PIN);
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
||||||
counter_x -= current_block->step_event_count;
|
counter_x -= current_block->step_event_count;
|
||||||
count_position[X_AXIS]+=count_direction[X_AXIS];
|
count_position[X_AXIS]+=count_direction[X_AXIS];
|
||||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
#ifdef DUAL_X_CARRIAGE
|
||||||
|
if (active_extruder != 0)
|
||||||
|
WRITE(X2_STEP_PIN,INVERT_X_STEP_PIN);
|
||||||
|
else
|
||||||
|
#endif
|
||||||
|
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
||||||
}
|
}
|
||||||
|
|
||||||
counter_y += current_block->steps_y;
|
counter_y += current_block->steps_y;
|
||||||
|
@ -532,56 +552,7 @@ ISR(TIMER1_COMPA_vect)
|
||||||
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
||||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef COREXY
|
|
||||||
counter_x += current_block->steps_x;
|
|
||||||
counter_y += current_block->steps_y;
|
|
||||||
|
|
||||||
if ((counter_x > 0)&&!(counter_y>0)){ //X step only
|
|
||||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
|
||||||
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
|
||||||
counter_x -= current_block->step_event_count;
|
|
||||||
count_position[X_AXIS]+=count_direction[X_AXIS];
|
|
||||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
|
||||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!(counter_x > 0)&&(counter_y>0)){ //Y step only
|
|
||||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
|
||||||
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
|
||||||
counter_y -= current_block->step_event_count;
|
|
||||||
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
|
||||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
|
||||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
|
||||||
}
|
|
||||||
|
|
||||||
if ((counter_x > 0)&&(counter_y>0)){ //step in both axes
|
|
||||||
if (((out_bits & (1<<X_AXIS)) == 0)^((out_bits & (1<<Y_AXIS)) == 0)){ //X and Y in different directions
|
|
||||||
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
|
||||||
counter_x -= current_block->step_event_count;
|
|
||||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
|
||||||
step_wait();
|
|
||||||
count_position[X_AXIS]+=count_direction[X_AXIS];
|
|
||||||
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
|
||||||
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
|
||||||
counter_y -= current_block->step_event_count;
|
|
||||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
|
||||||
}
|
|
||||||
else{ //X and Y in same direction
|
|
||||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
|
||||||
counter_x -= current_block->step_event_count;
|
|
||||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN) ;
|
|
||||||
step_wait();
|
|
||||||
count_position[X_AXIS]+=count_direction[X_AXIS];
|
|
||||||
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
|
||||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
|
||||||
counter_y -= current_block->step_event_count;
|
|
||||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#endif //corexy
|
|
||||||
|
|
||||||
counter_z += current_block->steps_z;
|
counter_z += current_block->steps_z;
|
||||||
if (counter_z > 0) {
|
if (counter_z > 0) {
|
||||||
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
|
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||||
|
@ -746,6 +717,9 @@ void st_init()
|
||||||
#if defined(X_DIR_PIN) && X_DIR_PIN > -1
|
#if defined(X_DIR_PIN) && X_DIR_PIN > -1
|
||||||
SET_OUTPUT(X_DIR_PIN);
|
SET_OUTPUT(X_DIR_PIN);
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(X2_DIR_PIN) && X2_DIR_PIN > -1
|
||||||
|
SET_OUTPUT(X2_DIR_PIN);
|
||||||
|
#endif
|
||||||
#if defined(Y_DIR_PIN) && Y_DIR_PIN > -1
|
#if defined(Y_DIR_PIN) && Y_DIR_PIN > -1
|
||||||
SET_OUTPUT(Y_DIR_PIN);
|
SET_OUTPUT(Y_DIR_PIN);
|
||||||
#endif
|
#endif
|
||||||
|
@ -772,6 +746,10 @@ void st_init()
|
||||||
SET_OUTPUT(X_ENABLE_PIN);
|
SET_OUTPUT(X_ENABLE_PIN);
|
||||||
if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
|
if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(X2_ENABLE_PIN) && X2_ENABLE_PIN > -1
|
||||||
|
SET_OUTPUT(X2_ENABLE_PIN);
|
||||||
|
if(!X_ENABLE_ON) WRITE(X2_ENABLE_PIN,HIGH);
|
||||||
|
#endif
|
||||||
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
|
#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
|
||||||
SET_OUTPUT(Y_ENABLE_PIN);
|
SET_OUTPUT(Y_ENABLE_PIN);
|
||||||
if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
|
if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
|
||||||
|
@ -849,6 +827,11 @@ void st_init()
|
||||||
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
|
WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
|
||||||
disable_x();
|
disable_x();
|
||||||
#endif
|
#endif
|
||||||
|
#if defined(X2_STEP_PIN) && (X2_STEP_PIN > -1)
|
||||||
|
SET_OUTPUT(X2_STEP_PIN);
|
||||||
|
WRITE(X2_STEP_PIN,INVERT_X_STEP_PIN);
|
||||||
|
disable_x();
|
||||||
|
#endif
|
||||||
#if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
|
#if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1)
|
||||||
SET_OUTPUT(Y_STEP_PIN);
|
SET_OUTPUT(Y_STEP_PIN);
|
||||||
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
|
WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
|
||||||
|
|
|
@ -40,10 +40,13 @@
|
||||||
int target_temperature[EXTRUDERS] = { 0 };
|
int target_temperature[EXTRUDERS] = { 0 };
|
||||||
int target_temperature_bed = 0;
|
int target_temperature_bed = 0;
|
||||||
int current_temperature_raw[EXTRUDERS] = { 0 };
|
int current_temperature_raw[EXTRUDERS] = { 0 };
|
||||||
float current_temperature[EXTRUDERS] = { 0 };
|
float current_temperature[EXTRUDERS] = { 0.0 };
|
||||||
int current_temperature_bed_raw = 0;
|
int current_temperature_bed_raw = 0;
|
||||||
float current_temperature_bed = 0;
|
float current_temperature_bed = 0.0;
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
int redundant_temperature_raw = 0;
|
||||||
|
float redundant_temperature = 0.0;
|
||||||
|
#endif
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
float Kp=DEFAULT_Kp;
|
float Kp=DEFAULT_Kp;
|
||||||
float Ki=(DEFAULT_Ki*PID_dT);
|
float Ki=(DEFAULT_Ki*PID_dT);
|
||||||
|
@ -59,6 +62,9 @@ float current_temperature_bed = 0;
|
||||||
float bedKd=(DEFAULT_bedKd/PID_dT);
|
float bedKd=(DEFAULT_bedKd/PID_dT);
|
||||||
#endif //PIDTEMPBED
|
#endif //PIDTEMPBED
|
||||||
|
|
||||||
|
#ifdef FAN_SOFT_PWM
|
||||||
|
unsigned char fanSpeedSoftPwm;
|
||||||
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//=============================private variables============================
|
//=============================private variables============================
|
||||||
|
@ -104,15 +110,15 @@ static volatile bool temp_meas_ready = false;
|
||||||
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
|
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
|
||||||
static unsigned long extruder_autofan_last_check;
|
static unsigned long extruder_autofan_last_check;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if EXTRUDERS > 3
|
#if EXTRUDERS > 3
|
||||||
# error Unsupported number of extruders
|
# error Unsupported number of extruders
|
||||||
#elif EXTRUDERS > 2
|
#elif EXTRUDERS > 2
|
||||||
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2, v3 }
|
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2, v3 }
|
||||||
#elif EXTRUDERS > 1
|
#elif EXTRUDERS > 1
|
||||||
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2 }
|
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2 }
|
||||||
#else
|
#else
|
||||||
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1 }
|
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1 }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Init min and max temp with extreme values to prevent false errors during startup
|
// Init min and max temp with extreme values to prevent false errors during startup
|
||||||
|
@ -124,8 +130,14 @@ static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 16383, 16383, 16383 );
|
||||||
#ifdef BED_MAXTEMP
|
#ifdef BED_MAXTEMP
|
||||||
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
|
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
|
||||||
#endif
|
#endif
|
||||||
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
|
|
||||||
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
static void *heater_ttbl_map[2] = {(void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE };
|
||||||
|
static uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN };
|
||||||
|
#else
|
||||||
|
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
|
||||||
|
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
|
||||||
|
#endif
|
||||||
|
|
||||||
static float analog2temp(int raw, uint8_t e);
|
static float analog2temp(int raw, uint8_t e);
|
||||||
static float analog2tempBed(int raw);
|
static float analog2tempBed(int raw);
|
||||||
|
@ -136,6 +148,10 @@ int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
|
||||||
unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
|
unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
|
||||||
#endif //WATCH_TEMP_PERIOD
|
#endif //WATCH_TEMP_PERIOD
|
||||||
|
|
||||||
|
#ifndef SOFT_PWM_SCALE
|
||||||
|
#define SOFT_PWM_SCALE 0
|
||||||
|
#endif
|
||||||
|
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
//============================= functions ============================
|
//============================= functions ============================
|
||||||
//===========================================================================
|
//===========================================================================
|
||||||
|
@ -157,28 +173,28 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
float Kp, Ki, Kd;
|
float Kp, Ki, Kd;
|
||||||
float max = 0, min = 10000;
|
float max = 0, min = 10000;
|
||||||
|
|
||||||
if ((extruder > EXTRUDERS)
|
if ((extruder > EXTRUDERS)
|
||||||
#if (TEMP_BED_PIN <= -1)
|
#if (TEMP_BED_PIN <= -1)
|
||||||
||(extruder < 0)
|
||(extruder < 0)
|
||||||
#endif
|
#endif
|
||||||
){
|
){
|
||||||
SERIAL_ECHOLN("PID Autotune failed. Bad extruder number.");
|
SERIAL_ECHOLN("PID Autotune failed. Bad extruder number.");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
SERIAL_ECHOLN("PID Autotune start");
|
SERIAL_ECHOLN("PID Autotune start");
|
||||||
|
|
||||||
disable_heater(); // switch off all heaters.
|
disable_heater(); // switch off all heaters.
|
||||||
|
|
||||||
if (extruder<0)
|
if (extruder<0)
|
||||||
{
|
{
|
||||||
soft_pwm_bed = (MAX_BED_POWER)/2;
|
soft_pwm_bed = (MAX_BED_POWER)/2;
|
||||||
bias = d = (MAX_BED_POWER)/2;
|
bias = d = (MAX_BED_POWER)/2;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
soft_pwm[extruder] = (PID_MAX)/2;
|
soft_pwm[extruder] = (PID_MAX)/2;
|
||||||
bias = d = (PID_MAX)/2;
|
bias = d = (PID_MAX)/2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -196,10 +212,10 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
if(heating == true && input > temp) {
|
if(heating == true && input > temp) {
|
||||||
if(millis() - t2 > 5000) {
|
if(millis() - t2 > 5000) {
|
||||||
heating=false;
|
heating=false;
|
||||||
if (extruder<0)
|
if (extruder<0)
|
||||||
soft_pwm_bed = (bias - d) >> 1;
|
soft_pwm_bed = (bias - d) >> 1;
|
||||||
else
|
else
|
||||||
soft_pwm[extruder] = (bias - d) >> 1;
|
soft_pwm[extruder] = (bias - d) >> 1;
|
||||||
t1=millis();
|
t1=millis();
|
||||||
t_high=t1 - t2;
|
t_high=t1 - t2;
|
||||||
max=temp;
|
max=temp;
|
||||||
|
@ -250,28 +266,28 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
*/
|
*/
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (extruder<0)
|
if (extruder<0)
|
||||||
soft_pwm_bed = (bias + d) >> 1;
|
soft_pwm_bed = (bias + d) >> 1;
|
||||||
else
|
else
|
||||||
soft_pwm[extruder] = (bias + d) >> 1;
|
soft_pwm[extruder] = (bias + d) >> 1;
|
||||||
cycles++;
|
cycles++;
|
||||||
min=temp;
|
min=temp;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if(input > (temp + 20)) {
|
if(input > (temp + 20)) {
|
||||||
SERIAL_PROTOCOLLNPGM("PID Autotune failed! Temperature to high");
|
SERIAL_PROTOCOLLNPGM("PID Autotune failed! Temperature too high");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if(millis() - temp_millis > 2000) {
|
if(millis() - temp_millis > 2000) {
|
||||||
int p;
|
int p;
|
||||||
if (extruder<0){
|
if (extruder<0){
|
||||||
p=soft_pwm_bed;
|
p=soft_pwm_bed;
|
||||||
SERIAL_PROTOCOLPGM("ok B:");
|
SERIAL_PROTOCOLPGM("ok B:");
|
||||||
}else{
|
}else{
|
||||||
p=soft_pwm[extruder];
|
p=soft_pwm[extruder];
|
||||||
SERIAL_PROTOCOLPGM("ok T:");
|
SERIAL_PROTOCOLPGM("ok T:");
|
||||||
}
|
}
|
||||||
|
|
||||||
SERIAL_PROTOCOL(input);
|
SERIAL_PROTOCOL(input);
|
||||||
SERIAL_PROTOCOLPGM(" @:");
|
SERIAL_PROTOCOLPGM(" @:");
|
||||||
|
@ -284,7 +300,7 @@ void PID_autotune(float temp, int extruder, int ncycles)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if(cycles > ncycles) {
|
if(cycles > ncycles) {
|
||||||
SERIAL_PROTOCOLLNPGM("PID Autotune finished ! Place the Kp, Ki and Kd constants in the configuration.h");
|
SERIAL_PROTOCOLLNPGM("PID Autotune finished! Put the Kp, Ki and Kd constants into Configuration.h");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
lcd_update();
|
lcd_update();
|
||||||
|
@ -471,7 +487,19 @@ void manage_heater()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
if(fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) {
|
||||||
|
disable_heater();
|
||||||
|
if(IsStopped() == false) {
|
||||||
|
SERIAL_ERROR_START;
|
||||||
|
SERIAL_ERRORLNPGM("Extruder switched off. Temperature difference between temp sensors is too high !");
|
||||||
|
LCD_ALERTMESSAGEPGM("Err: REDUNDANT TEMP ERROR");
|
||||||
|
}
|
||||||
|
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
||||||
|
Stop();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
} // End extruder for loop
|
} // End extruder for loop
|
||||||
|
|
||||||
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
|
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
|
||||||
|
@ -565,7 +593,11 @@ void manage_heater()
|
||||||
// Derived from RepRap FiveD extruder::getTemperature()
|
// Derived from RepRap FiveD extruder::getTemperature()
|
||||||
// For hot end temperature measurement.
|
// For hot end temperature measurement.
|
||||||
static float analog2temp(int raw, uint8_t e) {
|
static float analog2temp(int raw, uint8_t e) {
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
if(e > EXTRUDERS)
|
||||||
|
#else
|
||||||
if(e >= EXTRUDERS)
|
if(e >= EXTRUDERS)
|
||||||
|
#endif
|
||||||
{
|
{
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
SERIAL_ERROR((int)e);
|
SERIAL_ERROR((int)e);
|
||||||
|
@ -644,7 +676,9 @@ static void updateTemperaturesFromRawValues()
|
||||||
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
||||||
}
|
}
|
||||||
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
redundant_temperature = analog2temp(redundant_temperature_raw, 1);
|
||||||
|
#endif
|
||||||
//Reset the watchdog after we know we have a temperature measurement.
|
//Reset the watchdog after we know we have a temperature measurement.
|
||||||
watchdog_reset();
|
watchdog_reset();
|
||||||
|
|
||||||
|
@ -693,8 +727,8 @@ void tp_init()
|
||||||
setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
|
setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
|
||||||
#endif
|
#endif
|
||||||
#ifdef FAN_SOFT_PWM
|
#ifdef FAN_SOFT_PWM
|
||||||
soft_pwm_fan=(unsigned char)fanSpeed;
|
soft_pwm_fan = fanSpeedSoftPwm / 2;
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef HEATER_0_USES_MAX6675
|
#ifdef HEATER_0_USES_MAX6675
|
||||||
|
@ -994,14 +1028,14 @@ int read_max6675()
|
||||||
// Timer 0 is shared with millies
|
// Timer 0 is shared with millies
|
||||||
ISR(TIMER0_COMPB_vect)
|
ISR(TIMER0_COMPB_vect)
|
||||||
{
|
{
|
||||||
//these variables are only accesible from the ISR, but static, so they don't loose their value
|
//these variables are only accesible from the ISR, but static, so they don't lose their value
|
||||||
static unsigned char temp_count = 0;
|
static unsigned char temp_count = 0;
|
||||||
static unsigned long raw_temp_0_value = 0;
|
static unsigned long raw_temp_0_value = 0;
|
||||||
static unsigned long raw_temp_1_value = 0;
|
static unsigned long raw_temp_1_value = 0;
|
||||||
static unsigned long raw_temp_2_value = 0;
|
static unsigned long raw_temp_2_value = 0;
|
||||||
static unsigned long raw_temp_bed_value = 0;
|
static unsigned long raw_temp_bed_value = 0;
|
||||||
static unsigned char temp_state = 0;
|
static unsigned char temp_state = 0;
|
||||||
static unsigned char pwm_count = 1;
|
static unsigned char pwm_count = (1 << SOFT_PWM_SCALE);
|
||||||
static unsigned char soft_pwm_0;
|
static unsigned char soft_pwm_0;
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
static unsigned char soft_pwm_1;
|
static unsigned char soft_pwm_1;
|
||||||
|
@ -1029,7 +1063,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
|
if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
|
||||||
#endif
|
#endif
|
||||||
#ifdef FAN_SOFT_PWM
|
#ifdef FAN_SOFT_PWM
|
||||||
soft_pwm_fan =(unsigned char) fanSpeed;
|
soft_pwm_fan = fanSpeedSoftPwm / 2;
|
||||||
if(soft_pwm_fan > 0) WRITE(FAN_PIN,1);
|
if(soft_pwm_fan > 0) WRITE(FAN_PIN,1);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -1047,7 +1081,7 @@ ISR(TIMER0_COMPB_vect)
|
||||||
if(soft_pwm_fan <= pwm_count) WRITE(FAN_PIN,0);
|
if(soft_pwm_fan <= pwm_count) WRITE(FAN_PIN,0);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
pwm_count++;
|
pwm_count += (1 << SOFT_PWM_SCALE);
|
||||||
pwm_count &= 0x7f;
|
pwm_count &= 0x7f;
|
||||||
|
|
||||||
switch(temp_state) {
|
switch(temp_state) {
|
||||||
|
@ -1145,6 +1179,9 @@ ISR(TIMER0_COMPB_vect)
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
current_temperature_raw[1] = raw_temp_1_value;
|
current_temperature_raw[1] = raw_temp_1_value;
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
redundant_temperature_raw = raw_temp_1_value;
|
||||||
|
#endif
|
||||||
#if EXTRUDERS > 2
|
#if EXTRUDERS > 2
|
||||||
current_temperature_raw[2] = raw_temp_2_value;
|
current_temperature_raw[2] = raw_temp_2_value;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -37,6 +37,9 @@ extern int target_temperature[EXTRUDERS];
|
||||||
extern float current_temperature[EXTRUDERS];
|
extern float current_temperature[EXTRUDERS];
|
||||||
extern int target_temperature_bed;
|
extern int target_temperature_bed;
|
||||||
extern float current_temperature_bed;
|
extern float current_temperature_bed;
|
||||||
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
|
extern float redundant_temperature;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
extern float Kp,Ki,Kd,Kc;
|
extern float Kp,Ki,Kd,Kc;
|
||||||
|
|
|
@ -8,6 +8,8 @@
|
||||||
#include "stepper.h"
|
#include "stepper.h"
|
||||||
#include "ConfigurationStore.h"
|
#include "ConfigurationStore.h"
|
||||||
|
|
||||||
|
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
|
||||||
|
|
||||||
/* Configuration settings */
|
/* Configuration settings */
|
||||||
int plaPreheatHotendTemp;
|
int plaPreheatHotendTemp;
|
||||||
int plaPreheatHPBTemp;
|
int plaPreheatHPBTemp;
|
||||||
|
@ -47,6 +49,9 @@ static void lcd_control_temperature_menu();
|
||||||
static void lcd_control_temperature_preheat_pla_settings_menu();
|
static void lcd_control_temperature_preheat_pla_settings_menu();
|
||||||
static void lcd_control_temperature_preheat_abs_settings_menu();
|
static void lcd_control_temperature_preheat_abs_settings_menu();
|
||||||
static void lcd_control_motion_menu();
|
static void lcd_control_motion_menu();
|
||||||
|
#ifdef DOGLCD
|
||||||
|
static void lcd_set_contrast();
|
||||||
|
#endif
|
||||||
static void lcd_control_retract_menu();
|
static void lcd_control_retract_menu();
|
||||||
static void lcd_sdcard_menu();
|
static void lcd_sdcard_menu();
|
||||||
|
|
||||||
|
@ -122,13 +127,11 @@ static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned l
|
||||||
#ifndef REPRAPWORLD_KEYPAD
|
#ifndef REPRAPWORLD_KEYPAD
|
||||||
volatile uint8_t buttons;//Contains the bits of the currently pressed buttons.
|
volatile uint8_t buttons;//Contains the bits of the currently pressed buttons.
|
||||||
#else
|
#else
|
||||||
volatile uint16_t buttons;//Contains the bits of the currently pressed buttons (extended).
|
volatile uint8_t buttons_reprapworld_keypad; // to store the reprapworld_keypad shiftregister values
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
uint8_t currentMenuViewOffset; /* scroll offset in the current menu */
|
||||||
uint32_t blocking_enc;
|
uint32_t blocking_enc;
|
||||||
uint8_t lastEncoderBits;
|
uint8_t lastEncoderBits;
|
||||||
int8_t encoderDiff; /* encoderDiff is updated from interrupt context and added to encoderPosition every LCD update */
|
|
||||||
uint32_t encoderPosition;
|
uint32_t encoderPosition;
|
||||||
#if (SDCARDDETECT > 0)
|
#if (SDCARDDETECT > 0)
|
||||||
bool lcd_oldcardstatus;
|
bool lcd_oldcardstatus;
|
||||||
|
@ -173,8 +176,8 @@ static void lcd_status_screen()
|
||||||
}
|
}
|
||||||
|
|
||||||
// Dead zone at 100% feedrate
|
// Dead zone at 100% feedrate
|
||||||
if (feedmultiply < 100 && (feedmultiply + int(encoderPosition)) > 100 ||
|
if ((feedmultiply < 100 && (feedmultiply + int(encoderPosition)) > 100) ||
|
||||||
feedmultiply > 100 && (feedmultiply + int(encoderPosition)) < 100)
|
(feedmultiply > 100 && (feedmultiply + int(encoderPosition)) < 100))
|
||||||
{
|
{
|
||||||
encoderPosition = 0;
|
encoderPosition = 0;
|
||||||
feedmultiply = 100;
|
feedmultiply = 100;
|
||||||
|
@ -357,9 +360,9 @@ static void lcd_move_x()
|
||||||
if (encoderPosition != 0)
|
if (encoderPosition != 0)
|
||||||
{
|
{
|
||||||
current_position[X_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
current_position[X_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||||
if (current_position[X_AXIS] < X_MIN_POS)
|
if (min_software_endstops && current_position[X_AXIS] < X_MIN_POS)
|
||||||
current_position[X_AXIS] = X_MIN_POS;
|
current_position[X_AXIS] = X_MIN_POS;
|
||||||
if (current_position[X_AXIS] > X_MAX_POS)
|
if (max_software_endstops && current_position[X_AXIS] > X_MAX_POS)
|
||||||
current_position[X_AXIS] = X_MAX_POS;
|
current_position[X_AXIS] = X_MAX_POS;
|
||||||
encoderPosition = 0;
|
encoderPosition = 0;
|
||||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600, active_extruder);
|
||||||
|
@ -381,9 +384,9 @@ static void lcd_move_y()
|
||||||
if (encoderPosition != 0)
|
if (encoderPosition != 0)
|
||||||
{
|
{
|
||||||
current_position[Y_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
current_position[Y_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||||
if (current_position[Y_AXIS] < Y_MIN_POS)
|
if (min_software_endstops && current_position[Y_AXIS] < Y_MIN_POS)
|
||||||
current_position[Y_AXIS] = Y_MIN_POS;
|
current_position[Y_AXIS] = Y_MIN_POS;
|
||||||
if (current_position[Y_AXIS] > Y_MAX_POS)
|
if (max_software_endstops && current_position[Y_AXIS] > Y_MAX_POS)
|
||||||
current_position[Y_AXIS] = Y_MAX_POS;
|
current_position[Y_AXIS] = Y_MAX_POS;
|
||||||
encoderPosition = 0;
|
encoderPosition = 0;
|
||||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600, active_extruder);
|
||||||
|
@ -405,12 +408,12 @@ static void lcd_move_z()
|
||||||
if (encoderPosition != 0)
|
if (encoderPosition != 0)
|
||||||
{
|
{
|
||||||
current_position[Z_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
current_position[Z_AXIS] += float((int)encoderPosition) * move_menu_scale;
|
||||||
if (current_position[Z_AXIS] < Z_MIN_POS)
|
if (min_software_endstops && current_position[Z_AXIS] < Z_MIN_POS)
|
||||||
current_position[Z_AXIS] = Z_MIN_POS;
|
current_position[Z_AXIS] = Z_MIN_POS;
|
||||||
if (current_position[Z_AXIS] > Z_MAX_POS)
|
if (max_software_endstops && current_position[Z_AXIS] > Z_MAX_POS)
|
||||||
current_position[Z_AXIS] = Z_MAX_POS;
|
current_position[Z_AXIS] = Z_MAX_POS;
|
||||||
encoderPosition = 0;
|
encoderPosition = 0;
|
||||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 60, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS]/60, active_extruder);
|
||||||
lcdDrawUpdate = 1;
|
lcdDrawUpdate = 1;
|
||||||
}
|
}
|
||||||
if (lcdDrawUpdate)
|
if (lcdDrawUpdate)
|
||||||
|
@ -492,6 +495,10 @@ static void lcd_control_menu()
|
||||||
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
|
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
|
||||||
MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu);
|
MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu);
|
||||||
MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu);
|
MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu);
|
||||||
|
#ifdef DOGLCD
|
||||||
|
// MENU_ITEM_EDIT(int3, MSG_CONTRAST, &lcd_contrast, 0, 63);
|
||||||
|
MENU_ITEM(submenu, MSG_CONTRAST, lcd_set_contrast);
|
||||||
|
#endif
|
||||||
#ifdef FWRETRACT
|
#ifdef FWRETRACT
|
||||||
MENU_ITEM(submenu, MSG_RETRACT, lcd_control_retract_menu);
|
MENU_ITEM(submenu, MSG_RETRACT, lcd_control_retract_menu);
|
||||||
#endif
|
#endif
|
||||||
|
@ -505,9 +512,11 @@ static void lcd_control_menu()
|
||||||
|
|
||||||
static void lcd_control_temperature_menu()
|
static void lcd_control_temperature_menu()
|
||||||
{
|
{
|
||||||
|
#ifdef PIDTEMP
|
||||||
// set up temp variables - undo the default scaling
|
// set up temp variables - undo the default scaling
|
||||||
raw_Ki = unscalePID_i(Ki);
|
raw_Ki = unscalePID_i(Ki);
|
||||||
raw_Kd = unscalePID_d(Kd);
|
raw_Kd = unscalePID_d(Kd);
|
||||||
|
#endif
|
||||||
|
|
||||||
START_MENU();
|
START_MENU();
|
||||||
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
|
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
|
||||||
|
@ -601,6 +610,31 @@ static void lcd_control_motion_menu()
|
||||||
END_MENU();
|
END_MENU();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef DOGLCD
|
||||||
|
static void lcd_set_contrast()
|
||||||
|
{
|
||||||
|
if (encoderPosition != 0)
|
||||||
|
{
|
||||||
|
lcd_contrast -= encoderPosition;
|
||||||
|
if (lcd_contrast < 0) lcd_contrast = 0;
|
||||||
|
else if (lcd_contrast > 63) lcd_contrast = 63;
|
||||||
|
encoderPosition = 0;
|
||||||
|
lcdDrawUpdate = 1;
|
||||||
|
u8g.setContrast(lcd_contrast);
|
||||||
|
}
|
||||||
|
if (lcdDrawUpdate)
|
||||||
|
{
|
||||||
|
lcd_implementation_drawedit(PSTR("Contrast"), itostr2(lcd_contrast));
|
||||||
|
}
|
||||||
|
if (LCD_CLICKED)
|
||||||
|
{
|
||||||
|
lcd_quick_feedback();
|
||||||
|
currentMenu = lcd_control_menu;
|
||||||
|
encoderPosition = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef FWRETRACT
|
#ifdef FWRETRACT
|
||||||
static void lcd_control_retract_menu()
|
static void lcd_control_retract_menu()
|
||||||
{
|
{
|
||||||
|
@ -734,21 +768,39 @@ menu_edit_type(float, float52, ftostr52, 100)
|
||||||
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
|
menu_edit_type(unsigned long, long5, ftostr5, 0.01)
|
||||||
|
|
||||||
#ifdef REPRAPWORLD_KEYPAD
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
static void reprapworld_keypad_move_y_down() {
|
static void reprapworld_keypad_move_z_up() {
|
||||||
encoderPosition = 1;
|
encoderPosition = 1;
|
||||||
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
lcd_move_y();
|
lcd_move_z();
|
||||||
}
|
}
|
||||||
static void reprapworld_keypad_move_y_up() {
|
static void reprapworld_keypad_move_z_down() {
|
||||||
encoderPosition = -1;
|
encoderPosition = -1;
|
||||||
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
lcd_move_y();
|
lcd_move_z();
|
||||||
}
|
}
|
||||||
static void reprapworld_keypad_move_home() {
|
static void reprapworld_keypad_move_x_left() {
|
||||||
//enquecommand_P((PSTR("G28"))); // move all axis home
|
encoderPosition = -1;
|
||||||
// TODO gregor: move all axis home, i have currently only one axis on my prusa i3
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
enquecommand_P((PSTR("G28 Y")));
|
lcd_move_x();
|
||||||
}
|
}
|
||||||
|
static void reprapworld_keypad_move_x_right() {
|
||||||
|
encoderPosition = 1;
|
||||||
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
|
lcd_move_x();
|
||||||
|
}
|
||||||
|
static void reprapworld_keypad_move_y_down() {
|
||||||
|
encoderPosition = 1;
|
||||||
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
|
lcd_move_y();
|
||||||
|
}
|
||||||
|
static void reprapworld_keypad_move_y_up() {
|
||||||
|
encoderPosition = -1;
|
||||||
|
move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP;
|
||||||
|
lcd_move_y();
|
||||||
|
}
|
||||||
|
static void reprapworld_keypad_move_home() {
|
||||||
|
enquecommand_P((PSTR("G28"))); // move all axis home
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/** End of menus **/
|
/** End of menus **/
|
||||||
|
@ -875,17 +927,29 @@ void lcd_update()
|
||||||
if (lcd_next_update_millis < millis())
|
if (lcd_next_update_millis < millis())
|
||||||
{
|
{
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
#ifdef REPRAPWORLD_KEYPAD
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
if (REPRAPWORLD_KEYPAD_MOVE_Y_DOWN) {
|
if (REPRAPWORLD_KEYPAD_MOVE_Z_UP) {
|
||||||
reprapworld_keypad_move_y_down();
|
reprapworld_keypad_move_z_up();
|
||||||
}
|
}
|
||||||
if (REPRAPWORLD_KEYPAD_MOVE_Y_UP) {
|
if (REPRAPWORLD_KEYPAD_MOVE_Z_DOWN) {
|
||||||
reprapworld_keypad_move_y_up();
|
reprapworld_keypad_move_z_down();
|
||||||
}
|
}
|
||||||
if (REPRAPWORLD_KEYPAD_MOVE_HOME) {
|
if (REPRAPWORLD_KEYPAD_MOVE_X_LEFT) {
|
||||||
reprapworld_keypad_move_home();
|
reprapworld_keypad_move_x_left();
|
||||||
}
|
}
|
||||||
#endif
|
if (REPRAPWORLD_KEYPAD_MOVE_X_RIGHT) {
|
||||||
|
reprapworld_keypad_move_x_right();
|
||||||
|
}
|
||||||
|
if (REPRAPWORLD_KEYPAD_MOVE_Y_DOWN) {
|
||||||
|
reprapworld_keypad_move_y_down();
|
||||||
|
}
|
||||||
|
if (REPRAPWORLD_KEYPAD_MOVE_Y_UP) {
|
||||||
|
reprapworld_keypad_move_y_up();
|
||||||
|
}
|
||||||
|
if (REPRAPWORLD_KEYPAD_MOVE_HOME) {
|
||||||
|
reprapworld_keypad_move_home();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
if (encoderDiff)
|
if (encoderDiff)
|
||||||
{
|
{
|
||||||
lcdDrawUpdate = 1;
|
lcdDrawUpdate = 1;
|
||||||
|
@ -960,6 +1024,14 @@ void lcd_reset_alert_level()
|
||||||
lcd_status_message_level = 0;
|
lcd_status_message_level = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef DOGLCD
|
||||||
|
void lcd_setcontrast(uint8_t value)
|
||||||
|
{
|
||||||
|
lcd_contrast = value & 63;
|
||||||
|
u8g.setContrast(lcd_contrast);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
/* Warning: This function is called from interrupt context */
|
/* Warning: This function is called from interrupt context */
|
||||||
void lcd_buttons_update()
|
void lcd_buttons_update()
|
||||||
|
@ -971,22 +1043,22 @@ void lcd_buttons_update()
|
||||||
#if BTN_ENC > 0
|
#if BTN_ENC > 0
|
||||||
if((blocking_enc<millis()) && (READ(BTN_ENC)==0))
|
if((blocking_enc<millis()) && (READ(BTN_ENC)==0))
|
||||||
newbutton |= EN_C;
|
newbutton |= EN_C;
|
||||||
#endif
|
|
||||||
#ifdef REPRAPWORLD_KEYPAD
|
|
||||||
// for the reprapworld_keypad
|
|
||||||
uint8_t newbutton_reprapworld_keypad=0;
|
|
||||||
WRITE(SHIFT_LD,LOW);
|
|
||||||
WRITE(SHIFT_LD,HIGH);
|
|
||||||
for(int8_t i=0;i<8;i++) {
|
|
||||||
newbutton_reprapworld_keypad = newbutton_reprapworld_keypad>>1;
|
|
||||||
if(READ(SHIFT_OUT))
|
|
||||||
newbutton_reprapworld_keypad|=(1<<7);
|
|
||||||
WRITE(SHIFT_CLK,HIGH);
|
|
||||||
WRITE(SHIFT_CLK,LOW);
|
|
||||||
}
|
|
||||||
newbutton |= ((~newbutton_reprapworld_keypad) << REPRAPWORLD_BTN_OFFSET); //invert it, because a pressed switch produces a logical 0
|
|
||||||
#endif
|
#endif
|
||||||
buttons = newbutton;
|
buttons = newbutton;
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
// for the reprapworld_keypad
|
||||||
|
uint8_t newbutton_reprapworld_keypad=0;
|
||||||
|
WRITE(SHIFT_LD,LOW);
|
||||||
|
WRITE(SHIFT_LD,HIGH);
|
||||||
|
for(int8_t i=0;i<8;i++) {
|
||||||
|
newbutton_reprapworld_keypad = newbutton_reprapworld_keypad>>1;
|
||||||
|
if(READ(SHIFT_OUT))
|
||||||
|
newbutton_reprapworld_keypad|=(1<<7);
|
||||||
|
WRITE(SHIFT_CLK,HIGH);
|
||||||
|
WRITE(SHIFT_CLK,LOW);
|
||||||
|
}
|
||||||
|
buttons_reprapworld_keypad=~newbutton_reprapworld_keypad; //invert it, because a pressed switch produces a logical 0
|
||||||
|
#endif
|
||||||
#else //read it from the shift register
|
#else //read it from the shift register
|
||||||
uint8_t newbutton=0;
|
uint8_t newbutton=0;
|
||||||
WRITE(SHIFT_LD,LOW);
|
WRITE(SHIFT_LD,LOW);
|
||||||
|
@ -1252,16 +1324,20 @@ char *ftostr52(const float &x)
|
||||||
// grab the pid i value out of the temp variable; scale it; then update the PID driver
|
// grab the pid i value out of the temp variable; scale it; then update the PID driver
|
||||||
void copy_and_scalePID_i()
|
void copy_and_scalePID_i()
|
||||||
{
|
{
|
||||||
|
#ifdef PIDTEMP
|
||||||
Ki = scalePID_i(raw_Ki);
|
Ki = scalePID_i(raw_Ki);
|
||||||
updatePID();
|
updatePID();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// Callback for after editing PID d value
|
// Callback for after editing PID d value
|
||||||
// grab the pid d value out of the temp variable; scale it; then update the PID driver
|
// grab the pid d value out of the temp variable; scale it; then update the PID driver
|
||||||
void copy_and_scalePID_d()
|
void copy_and_scalePID_d()
|
||||||
{
|
{
|
||||||
|
#ifdef PIDTEMP
|
||||||
Kd = scalePID_d(raw_Kd);
|
Kd = scalePID_d(raw_Kd);
|
||||||
updatePID();
|
updatePID();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif //ULTRA_LCD
|
#endif //ULTRA_LCD
|
||||||
|
|
|
@ -11,7 +11,12 @@
|
||||||
void lcd_setstatuspgm(const char* message);
|
void lcd_setstatuspgm(const char* message);
|
||||||
void lcd_setalertstatuspgm(const char* message);
|
void lcd_setalertstatuspgm(const char* message);
|
||||||
void lcd_reset_alert_level();
|
void lcd_reset_alert_level();
|
||||||
|
|
||||||
|
#ifdef DOGLCD
|
||||||
|
extern int lcd_contrast;
|
||||||
|
void lcd_setcontrast(uint8_t value);
|
||||||
|
#endif
|
||||||
|
|
||||||
static unsigned char blink = 0; // Variable for visualisation of fan rotation in GLCD
|
static unsigned char blink = 0; // Variable for visualisation of fan rotation in GLCD
|
||||||
|
|
||||||
#define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x))
|
#define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x))
|
||||||
|
@ -22,6 +27,10 @@
|
||||||
|
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
void lcd_buttons_update();
|
void lcd_buttons_update();
|
||||||
|
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
extern volatile uint8_t buttons_reprapworld_keypad; // to store the keypad shiftregister values
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
FORCE_INLINE void lcd_buttons_update() {}
|
FORCE_INLINE void lcd_buttons_update() {}
|
||||||
#endif
|
#endif
|
||||||
|
@ -37,6 +46,45 @@
|
||||||
void lcd_buzz(long duration,uint16_t freq);
|
void lcd_buzz(long duration,uint16_t freq);
|
||||||
bool lcd_clicked();
|
bool lcd_clicked();
|
||||||
|
|
||||||
|
#ifdef NEWPANEL
|
||||||
|
#define EN_C (1<<BLEN_C)
|
||||||
|
#define EN_B (1<<BLEN_B)
|
||||||
|
#define EN_A (1<<BLEN_A)
|
||||||
|
|
||||||
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
|
#ifdef REPRAPWORLD_KEYPAD
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<BLEN_REPRAPWORLD_KEYPAD_F3)
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<BLEN_REPRAPWORLD_KEYPAD_F2)
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<BLEN_REPRAPWORLD_KEYPAD_F1)
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_UP (1<<BLEN_REPRAPWORLD_KEYPAD_UP)
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<BLEN_REPRAPWORLD_KEYPAD_RIGHT)
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<BLEN_REPRAPWORLD_KEYPAD_MIDDLE)
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<BLEN_REPRAPWORLD_KEYPAD_DOWN)
|
||||||
|
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<BLEN_REPRAPWORLD_KEYPAD_LEFT)
|
||||||
|
|
||||||
|
#define LCD_CLICKED ((buttons&EN_C) || (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F1))
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_Z_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F2)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_Z_DOWN (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_F3)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_X_LEFT (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_LEFT)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_X_RIGHT (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_RIGHT)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_DOWN)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_UP)
|
||||||
|
#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_MIDDLE)
|
||||||
|
#endif //REPRAPWORLD_KEYPAD
|
||||||
|
#else
|
||||||
|
//atomatic, do not change
|
||||||
|
#define B_LE (1<<BL_LE)
|
||||||
|
#define B_UP (1<<BL_UP)
|
||||||
|
#define B_MI (1<<BL_MI)
|
||||||
|
#define B_DW (1<<BL_DW)
|
||||||
|
#define B_RI (1<<BL_RI)
|
||||||
|
#define B_ST (1<<BL_ST)
|
||||||
|
#define EN_B (1<<BLEN_B)
|
||||||
|
#define EN_A (1<<BLEN_A)
|
||||||
|
|
||||||
|
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
|
||||||
|
#endif//NEWPANEL
|
||||||
|
|
||||||
#else //no lcd
|
#else //no lcd
|
||||||
FORCE_INLINE void lcd_update() {}
|
FORCE_INLINE void lcd_update() {}
|
||||||
FORCE_INLINE void lcd_init() {}
|
FORCE_INLINE void lcd_init() {}
|
||||||
|
|
|
@ -1,748 +1,757 @@
|
||||||
#ifndef ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
#ifndef ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
||||||
#define ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
#define ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Implementation of the LCD display routines for a hitachi HD44780 display. These are common LCD character displays.
|
* Implementation of the LCD display routines for a hitachi HD44780 display. These are common LCD character displays.
|
||||||
* When selecting the rusian language, a slightly different LCD implementation is used to handle UTF8 characters.
|
* When selecting the rusian language, a slightly different LCD implementation is used to handle UTF8 characters.
|
||||||
**/
|
**/
|
||||||
|
|
||||||
#ifndef REPRAPWORLD_KEYPAD
|
#ifndef REPRAPWORLD_KEYPAD
|
||||||
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
extern volatile uint8_t buttons; //the last checked buttons in a bit array.
|
||||||
#else
|
#else
|
||||||
extern volatile uint16_t buttons; //an extended version of the last checked buttons in a bit array.
|
extern volatile uint16_t buttons; //an extended version of the last checked buttons in a bit array.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
////////////////////////////////////
|
////////////////////////////////////
|
||||||
// Setup button and encode mappings for each panel (into 'buttons' variable)
|
// Setup button and encode mappings for each panel (into 'buttons' variable
|
||||||
//
|
//
|
||||||
// This is just to map common functions (across different panels) onto the same
|
// This is just to map common functions (across different panels) onto the same
|
||||||
// macro name. The mapping is independent of whether the button is directly connected or
|
// macro name. The mapping is independent of whether the button is directly connected or
|
||||||
// via a shift/i2c register.
|
// via a shift/i2c register.
|
||||||
|
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
// All Ultipanels might have an encoder - so this is always be mapped onto first two bits
|
// All Ultipanels might have an encoder - so this is always be mapped onto first two bits
|
||||||
#define BLEN_B 1
|
#define BLEN_B 1
|
||||||
#define BLEN_A 0
|
#define BLEN_A 0
|
||||||
|
|
||||||
#define EN_B (1<<BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2
|
#define EN_B (1<<BLEN_B) // The two encoder pins are connected through BTN_EN1 and BTN_EN2
|
||||||
#define EN_A (1<<BLEN_A)
|
#define EN_A (1<<BLEN_A)
|
||||||
|
|
||||||
#if defined(BTN_ENC) && BTN_ENC > -1
|
#if defined(BTN_ENC) && BTN_ENC > -1
|
||||||
// encoder click is directly connected
|
// encoder click is directly connected
|
||||||
#define BLEN_C 2
|
#define BLEN_C 2
|
||||||
#define EN_C (1<<BLEN_C)
|
#define EN_C (1<<BLEN_C)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//
|
//
|
||||||
// Setup other button mappings of each panel
|
// Setup other button mappings of each panel
|
||||||
//
|
//
|
||||||
#if defined(LCD_I2C_VIKI)
|
#if defined(LCD_I2C_VIKI)
|
||||||
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
|
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
|
||||||
|
|
||||||
// button and encoder bit positions within 'buttons'
|
// button and encoder bit positions within 'buttons'
|
||||||
#define B_LE (BUTTON_LEFT<<B_I2C_BTN_OFFSET) // The remaining normalized buttons are all read via I2C
|
#define B_LE (BUTTON_LEFT<<B_I2C_BTN_OFFSET) // The remaining normalized buttons are all read via I2C
|
||||||
#define B_UP (BUTTON_UP<<B_I2C_BTN_OFFSET)
|
#define B_UP (BUTTON_UP<<B_I2C_BTN_OFFSET)
|
||||||
#define B_MI (BUTTON_SELECT<<B_I2C_BTN_OFFSET)
|
#define B_MI (BUTTON_SELECT<<B_I2C_BTN_OFFSET)
|
||||||
#define B_DW (BUTTON_DOWN<<B_I2C_BTN_OFFSET)
|
#define B_DW (BUTTON_DOWN<<B_I2C_BTN_OFFSET)
|
||||||
#define B_RI (BUTTON_RIGHT<<B_I2C_BTN_OFFSET)
|
#define B_RI (BUTTON_RIGHT<<B_I2C_BTN_OFFSET)
|
||||||
|
|
||||||
#if defined(BTN_ENC) && BTN_ENC > -1
|
#if defined(BTN_ENC) && BTN_ENC > -1
|
||||||
// the pause/stop/restart button is connected to BTN_ENC when used
|
// the pause/stop/restart button is connected to BTN_ENC when used
|
||||||
#define B_ST (EN_C) // Map the pause/stop/resume button into its normalized functional name
|
#define B_ST (EN_C) // Map the pause/stop/resume button into its normalized functional name
|
||||||
#define LCD_CLICKED (buttons&(B_MI|B_RI|B_ST)) // pause/stop button also acts as click until we implement proper pause/stop.
|
#define LCD_CLICKED (buttons&(B_MI|B_RI|B_ST)) // pause/stop button also acts as click until we implement proper pause/stop.
|
||||||
#else
|
#else
|
||||||
#define LCD_CLICKED (buttons&(B_MI|B_RI))
|
#define LCD_CLICKED (buttons&(B_MI|B_RI))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
|
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
|
||||||
#define LCD_HAS_SLOW_BUTTONS
|
#define LCD_HAS_SLOW_BUTTONS
|
||||||
|
|
||||||
#elif defined(LCD_I2C_PANELOLU2)
|
#elif defined(LCD_I2C_PANELOLU2)
|
||||||
// encoder click can be read through I2C if not directly connected
|
// encoder click can be read through I2C if not directly connected
|
||||||
#if BTN_ENC <= 0
|
#if BTN_ENC <= 0
|
||||||
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
|
#define B_I2C_BTN_OFFSET 3 // (the first three bit positions reserved for EN_A, EN_B, EN_C)
|
||||||
|
|
||||||
#define B_MI (PANELOLU2_ENCODER_C<<B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later
|
#define B_MI (PANELOLU2_ENCODER_C<<B_I2C_BTN_OFFSET) // requires LiquidTWI2 library v1.2.3 or later
|
||||||
|
|
||||||
#define LCD_CLICKED (buttons&B_MI)
|
#define LCD_CLICKED (buttons&B_MI)
|
||||||
|
|
||||||
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
|
// I2C buttons take too long to read inside an interrupt context and so we read them during lcd_update
|
||||||
#define LCD_HAS_SLOW_BUTTONS
|
#define LCD_HAS_SLOW_BUTTONS
|
||||||
#else
|
#else
|
||||||
#define LCD_CLICKED (buttons&EN_C)
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#elif defined(REPRAPWORLD_KEYPAD)
|
#elif defined(REPRAPWORLD_KEYPAD)
|
||||||
// define register bit values, don't change it
|
// define register bit values, don't change it
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_F3 0
|
#define BLEN_REPRAPWORLD_KEYPAD_F3 0
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_F2 1
|
#define BLEN_REPRAPWORLD_KEYPAD_F2 1
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_F1 2
|
#define BLEN_REPRAPWORLD_KEYPAD_F1 2
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_UP 3
|
#define BLEN_REPRAPWORLD_KEYPAD_UP 3
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_RIGHT 4
|
#define BLEN_REPRAPWORLD_KEYPAD_RIGHT 4
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_MIDDLE 5
|
#define BLEN_REPRAPWORLD_KEYPAD_MIDDLE 5
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_DOWN 6
|
#define BLEN_REPRAPWORLD_KEYPAD_DOWN 6
|
||||||
#define BLEN_REPRAPWORLD_KEYPAD_LEFT 7
|
#define BLEN_REPRAPWORLD_KEYPAD_LEFT 7
|
||||||
|
|
||||||
#define REPRAPWORLD_BTN_OFFSET 3 // bit offset into buttons for shift register values
|
#define REPRAPWORLD_BTN_OFFSET 3 // bit offset into buttons for shift register values
|
||||||
|
|
||||||
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<(BLEN_REPRAPWORLD_KEYPAD_F3+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_F3 (1<<(BLEN_REPRAPWORLD_KEYPAD_F3+REPRAPWORLD_BTN_OFFSET))
|
||||||
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<(BLEN_REPRAPWORLD_KEYPAD_F2+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_F2 (1<<(BLEN_REPRAPWORLD_KEYPAD_F2+REPRAPWORLD_BTN_OFFSET))
|
||||||
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<(BLEN_REPRAPWORLD_KEYPAD_F1+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_F1 (1<<(BLEN_REPRAPWORLD_KEYPAD_F1+REPRAPWORLD_BTN_OFFSET))
|
||||||
#define EN_REPRAPWORLD_KEYPAD_UP (1<<(BLEN_REPRAPWORLD_KEYPAD_UP+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_UP (1<<(BLEN_REPRAPWORLD_KEYPAD_UP+REPRAPWORLD_BTN_OFFSET))
|
||||||
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<(BLEN_REPRAPWORLD_KEYPAD_RIGHT+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_RIGHT (1<<(BLEN_REPRAPWORLD_KEYPAD_RIGHT+REPRAPWORLD_BTN_OFFSET))
|
||||||
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<(BLEN_REPRAPWORLD_KEYPAD_MIDDLE+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_MIDDLE (1<<(BLEN_REPRAPWORLD_KEYPAD_MIDDLE+REPRAPWORLD_BTN_OFFSET))
|
||||||
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<(BLEN_REPRAPWORLD_KEYPAD_DOWN+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_DOWN (1<<(BLEN_REPRAPWORLD_KEYPAD_DOWN+REPRAPWORLD_BTN_OFFSET))
|
||||||
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<(BLEN_REPRAPWORLD_KEYPAD_LEFT+REPRAPWORLD_BTN_OFFSET))
|
#define EN_REPRAPWORLD_KEYPAD_LEFT (1<<(BLEN_REPRAPWORLD_KEYPAD_LEFT+REPRAPWORLD_BTN_OFFSET))
|
||||||
|
|
||||||
#define LCD_CLICKED ((buttons&EN_C) || (buttons&EN_REPRAPWORLD_KEYPAD_F1))
|
#define LCD_CLICKED ((buttons&EN_C) || (buttons&EN_REPRAPWORLD_KEYPAD_F1))
|
||||||
#define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons&EN_REPRAPWORLD_KEYPAD_DOWN)
|
#define REPRAPWORLD_KEYPAD_MOVE_Y_DOWN (buttons&EN_REPRAPWORLD_KEYPAD_DOWN)
|
||||||
#define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons&EN_REPRAPWORLD_KEYPAD_UP)
|
#define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons&EN_REPRAPWORLD_KEYPAD_UP)
|
||||||
#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons&EN_REPRAPWORLD_KEYPAD_MIDDLE)
|
#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons&EN_REPRAPWORLD_KEYPAD_MIDDLE)
|
||||||
|
|
||||||
#elif defined(NEWPANEL)
|
#elif defined(NEWPANEL)
|
||||||
#define LCD_CLICKED (buttons&EN_C)
|
#define LCD_CLICKED (buttons&EN_C)
|
||||||
|
|
||||||
#else // old style ULTIPANEL
|
#else // old style ULTIPANEL
|
||||||
//bits in the shift register that carry the buttons for:
|
//bits in the shift register that carry the buttons for:
|
||||||
// left up center down right red(stop)
|
// left up center down right red(stop)
|
||||||
#define BL_LE 7
|
#define BL_LE 7
|
||||||
#define BL_UP 6
|
#define BL_UP 6
|
||||||
#define BL_MI 5
|
#define BL_MI 5
|
||||||
#define BL_DW 4
|
#define BL_DW 4
|
||||||
#define BL_RI 3
|
#define BL_RI 3
|
||||||
#define BL_ST 2
|
#define BL_ST 2
|
||||||
|
|
||||||
//automatic, do not change
|
//automatic, do not change
|
||||||
#define B_LE (1<<BL_LE)
|
#define B_LE (1<<BL_LE)
|
||||||
#define B_UP (1<<BL_UP)
|
#define B_UP (1<<BL_UP)
|
||||||
#define B_MI (1<<BL_MI)
|
#define B_MI (1<<BL_MI)
|
||||||
#define B_DW (1<<BL_DW)
|
#define B_DW (1<<BL_DW)
|
||||||
#define B_RI (1<<BL_RI)
|
#define B_RI (1<<BL_RI)
|
||||||
#define B_ST (1<<BL_ST)
|
#define B_ST (1<<BL_ST)
|
||||||
|
|
||||||
#define LCD_CLICKED (buttons&(B_MI|B_ST))
|
#define LCD_CLICKED (buttons&(B_MI|B_ST))
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
////////////////////////
|
////////////////////////
|
||||||
// Setup Rotary Encoder Bit Values (for two pin encoders to indicate movement)
|
// 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
|
// 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
|
// The rotary encoder part is also independent to the chipset used for the LCD
|
||||||
#if defined(EN_A) && defined(EN_B)
|
#if defined(EN_A) && defined(EN_B)
|
||||||
#ifndef ULTIMAKERCONTROLLER
|
#ifndef ULTIMAKERCONTROLLER
|
||||||
#define encrot0 0
|
#define encrot0 0
|
||||||
#define encrot1 2
|
#define encrot1 2
|
||||||
#define encrot2 3
|
#define encrot2 3
|
||||||
#define encrot3 1
|
#define encrot3 1
|
||||||
#else
|
#else
|
||||||
#define encrot0 0
|
#define encrot0 0
|
||||||
#define encrot1 1
|
#define encrot1 1
|
||||||
#define encrot2 3
|
#define encrot2 3
|
||||||
#define encrot3 2
|
#define encrot3 2
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif //ULTIPANEL
|
#endif //ULTIPANEL
|
||||||
|
|
||||||
////////////////////////////////////
|
////////////////////////////////////
|
||||||
// Create LCD class instance and chipset-specific information
|
// Create LCD class instance and chipset-specific information
|
||||||
#if defined(LCD_I2C_TYPE_PCF8575)
|
#if defined(LCD_I2C_TYPE_PCF8575)
|
||||||
// note: these are register mapped pins on the PCF8575 controller not Arduino pins
|
// note: these are register mapped pins on the PCF8575 controller not Arduino pins
|
||||||
#define LCD_I2C_PIN_BL 3
|
#define LCD_I2C_PIN_BL 3
|
||||||
#define LCD_I2C_PIN_EN 2
|
#define LCD_I2C_PIN_EN 2
|
||||||
#define LCD_I2C_PIN_RW 1
|
#define LCD_I2C_PIN_RW 1
|
||||||
#define LCD_I2C_PIN_RS 0
|
#define LCD_I2C_PIN_RS 0
|
||||||
#define LCD_I2C_PIN_D4 4
|
#define LCD_I2C_PIN_D4 4
|
||||||
#define LCD_I2C_PIN_D5 5
|
#define LCD_I2C_PIN_D5 5
|
||||||
#define LCD_I2C_PIN_D6 6
|
#define LCD_I2C_PIN_D6 6
|
||||||
#define LCD_I2C_PIN_D7 7
|
#define LCD_I2C_PIN_D7 7
|
||||||
|
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <LCD.h>
|
#include <LCD.h>
|
||||||
#include <LiquidCrystal_I2C.h>
|
#include <LiquidCrystal_I2C.h>
|
||||||
#define LCD_CLASS LiquidCrystal_I2C
|
#define LCD_CLASS LiquidCrystal_I2C
|
||||||
LCD_CLASS lcd(LCD_I2C_ADDRESS,LCD_I2C_PIN_EN,LCD_I2C_PIN_RW,LCD_I2C_PIN_RS,LCD_I2C_PIN_D4,LCD_I2C_PIN_D5,LCD_I2C_PIN_D6,LCD_I2C_PIN_D7);
|
LCD_CLASS lcd(LCD_I2C_ADDRESS,LCD_I2C_PIN_EN,LCD_I2C_PIN_RW,LCD_I2C_PIN_RS,LCD_I2C_PIN_D4,LCD_I2C_PIN_D5,LCD_I2C_PIN_D6,LCD_I2C_PIN_D7);
|
||||||
|
|
||||||
#elif defined(LCD_I2C_TYPE_MCP23017)
|
#elif defined(LCD_I2C_TYPE_MCP23017)
|
||||||
//for the LED indicators (which maybe mapped to different things in lcd_implementation_update_indicators())
|
//for the LED indicators (which maybe mapped to different things in lcd_implementation_update_indicators())
|
||||||
#define LED_A 0x04 //100
|
#define LED_A 0x04 //100
|
||||||
#define LED_B 0x02 //010
|
#define LED_B 0x02 //010
|
||||||
#define LED_C 0x01 //001
|
#define LED_C 0x01 //001
|
||||||
|
|
||||||
#define LCD_HAS_STATUS_INDICATORS
|
#define LCD_HAS_STATUS_INDICATORS
|
||||||
|
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <LiquidTWI2.h>
|
#include <LiquidTWI2.h>
|
||||||
#define LCD_CLASS LiquidTWI2
|
#define LCD_CLASS LiquidTWI2
|
||||||
LCD_CLASS lcd(LCD_I2C_ADDRESS);
|
LCD_CLASS lcd(LCD_I2C_ADDRESS);
|
||||||
|
|
||||||
#elif defined(LCD_I2C_TYPE_MCP23008)
|
#elif defined(LCD_I2C_TYPE_MCP23008)
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
#include <LiquidTWI2.h>
|
#include <LiquidTWI2.h>
|
||||||
#define LCD_CLASS LiquidTWI2
|
#define LCD_CLASS LiquidTWI2
|
||||||
LCD_CLASS lcd(LCD_I2C_ADDRESS);
|
LCD_CLASS lcd(LCD_I2C_ADDRESS);
|
||||||
|
|
||||||
#else
|
#elif defined(LCD_I2C_TYPE_PCA8574)
|
||||||
// Standard directly connected LCD implementations
|
#include <LiquidCrystal_I2C.h>
|
||||||
#if LANGUAGE_CHOICE == 6
|
#define LCD_CLASS LiquidCrystal_I2C
|
||||||
#include "LiquidCrystalRus.h"
|
LCD_CLASS lcd(LCD_I2C_ADDRESS, LCD_WIDTH, LCD_HEIGHT);
|
||||||
#define LCD_CLASS LiquidCrystalRus
|
|
||||||
#else
|
#else
|
||||||
#include <LiquidCrystal.h>
|
// Standard directly connected LCD implementations
|
||||||
#define LCD_CLASS LiquidCrystal
|
#if LANGUAGE_CHOICE == 6
|
||||||
#endif
|
#include "LiquidCrystalRus.h"
|
||||||
LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
|
#define LCD_CLASS LiquidCrystalRus
|
||||||
#endif
|
#else
|
||||||
|
#include <LiquidCrystal.h>
|
||||||
/* Custom characters defined in the first 8 characters of the LCD */
|
#define LCD_CLASS LiquidCrystal
|
||||||
#define LCD_STR_BEDTEMP "\x00"
|
#endif
|
||||||
#define LCD_STR_DEGREE "\x01"
|
LCD_CLASS lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PINS_D6,LCD_PINS_D7); //RS,Enable,D4,D5,D6,D7
|
||||||
#define LCD_STR_THERMOMETER "\x02"
|
#endif
|
||||||
#define LCD_STR_UPLEVEL "\x03"
|
|
||||||
#define LCD_STR_REFRESH "\x04"
|
/* Custom characters defined in the first 8 characters of the LCD */
|
||||||
#define LCD_STR_FOLDER "\x05"
|
#define LCD_STR_BEDTEMP "\x00"
|
||||||
#define LCD_STR_FEEDRATE "\x06"
|
#define LCD_STR_DEGREE "\x01"
|
||||||
#define LCD_STR_CLOCK "\x07"
|
#define LCD_STR_THERMOMETER "\x02"
|
||||||
#define LCD_STR_ARROW_RIGHT "\x7E" /* from the default character set */
|
#define LCD_STR_UPLEVEL "\x03"
|
||||||
|
#define LCD_STR_REFRESH "\x04"
|
||||||
static void lcd_implementation_init()
|
#define LCD_STR_FOLDER "\x05"
|
||||||
{
|
#define LCD_STR_FEEDRATE "\x06"
|
||||||
byte bedTemp[8] =
|
#define LCD_STR_CLOCK "\x07"
|
||||||
{
|
#define LCD_STR_ARROW_RIGHT "\x7E" /* from the default character set */
|
||||||
B00000,
|
|
||||||
B11111,
|
static void lcd_implementation_init()
|
||||||
B10101,
|
{
|
||||||
B10001,
|
byte bedTemp[8] =
|
||||||
B10101,
|
{
|
||||||
B11111,
|
B00000,
|
||||||
B00000,
|
B11111,
|
||||||
B00000
|
B10101,
|
||||||
}; //thanks Sonny Mounicou
|
B10001,
|
||||||
byte degree[8] =
|
B10101,
|
||||||
{
|
B11111,
|
||||||
B01100,
|
B00000,
|
||||||
B10010,
|
B00000
|
||||||
B10010,
|
}; //thanks Sonny Mounicou
|
||||||
B01100,
|
byte degree[8] =
|
||||||
B00000,
|
{
|
||||||
B00000,
|
B01100,
|
||||||
B00000,
|
B10010,
|
||||||
B00000
|
B10010,
|
||||||
};
|
B01100,
|
||||||
byte thermometer[8] =
|
B00000,
|
||||||
{
|
B00000,
|
||||||
B00100,
|
B00000,
|
||||||
B01010,
|
B00000
|
||||||
B01010,
|
};
|
||||||
B01010,
|
byte thermometer[8] =
|
||||||
B01010,
|
{
|
||||||
B10001,
|
B00100,
|
||||||
B10001,
|
B01010,
|
||||||
B01110
|
B01010,
|
||||||
};
|
B01010,
|
||||||
byte uplevel[8]={
|
B01010,
|
||||||
B00100,
|
B10001,
|
||||||
B01110,
|
B10001,
|
||||||
B11111,
|
B01110
|
||||||
B00100,
|
};
|
||||||
B11100,
|
byte uplevel[8]={
|
||||||
B00000,
|
B00100,
|
||||||
B00000,
|
B01110,
|
||||||
B00000
|
B11111,
|
||||||
}; //thanks joris
|
B00100,
|
||||||
byte refresh[8]={
|
B11100,
|
||||||
B00000,
|
B00000,
|
||||||
B00110,
|
B00000,
|
||||||
B11001,
|
B00000
|
||||||
B11000,
|
}; //thanks joris
|
||||||
B00011,
|
byte refresh[8]={
|
||||||
B10011,
|
B00000,
|
||||||
B01100,
|
B00110,
|
||||||
B00000,
|
B11001,
|
||||||
}; //thanks joris
|
B11000,
|
||||||
byte folder [8]={
|
B00011,
|
||||||
B00000,
|
B10011,
|
||||||
B11100,
|
B01100,
|
||||||
B11111,
|
B00000,
|
||||||
B10001,
|
}; //thanks joris
|
||||||
B10001,
|
byte folder [8]={
|
||||||
B11111,
|
B00000,
|
||||||
B00000,
|
B11100,
|
||||||
B00000
|
B11111,
|
||||||
}; //thanks joris
|
B10001,
|
||||||
byte feedrate [8]={
|
B10001,
|
||||||
B11100,
|
B11111,
|
||||||
B10000,
|
B00000,
|
||||||
B11000,
|
B00000
|
||||||
B10111,
|
}; //thanks joris
|
||||||
B00101,
|
byte feedrate [8]={
|
||||||
B00110,
|
B11100,
|
||||||
B00101,
|
B10000,
|
||||||
B00000
|
B11000,
|
||||||
}; //thanks Sonny Mounicou
|
B10111,
|
||||||
byte clock [8]={
|
B00101,
|
||||||
B00000,
|
B00110,
|
||||||
B01110,
|
B00101,
|
||||||
B10011,
|
B00000
|
||||||
B10101,
|
}; //thanks Sonny Mounicou
|
||||||
B10001,
|
byte clock [8]={
|
||||||
B01110,
|
B00000,
|
||||||
B00000,
|
B01110,
|
||||||
B00000
|
B10011,
|
||||||
}; //thanks Sonny Mounicou
|
B10101,
|
||||||
|
B10001,
|
||||||
#if defined(LCDI2C_TYPE_PCF8575)
|
B01110,
|
||||||
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
B00000,
|
||||||
#ifdef LCD_I2C_PIN_BL
|
B00000
|
||||||
lcd.setBacklightPin(LCD_I2C_PIN_BL,POSITIVE);
|
}; //thanks Sonny Mounicou
|
||||||
lcd.setBacklight(HIGH);
|
|
||||||
#endif
|
#if defined(LCDI2C_TYPE_PCF8575)
|
||||||
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
#elif defined(LCD_I2C_TYPE_MCP23017)
|
#ifdef LCD_I2C_PIN_BL
|
||||||
lcd.setMCPType(LTI_TYPE_MCP23017);
|
lcd.setBacklightPin(LCD_I2C_PIN_BL,POSITIVE);
|
||||||
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
lcd.setBacklight(HIGH);
|
||||||
lcd.setBacklight(0); //set all the LEDs off to begin with
|
#endif
|
||||||
|
|
||||||
#elif defined(LCD_I2C_TYPE_MCP23008)
|
#elif defined(LCD_I2C_TYPE_MCP23017)
|
||||||
lcd.setMCPType(LTI_TYPE_MCP23008);
|
lcd.setMCPType(LTI_TYPE_MCP23017);
|
||||||
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
|
lcd.setBacklight(0); //set all the LEDs off to begin with
|
||||||
#else
|
|
||||||
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
#elif defined(LCD_I2C_TYPE_MCP23008)
|
||||||
#endif
|
lcd.setMCPType(LTI_TYPE_MCP23008);
|
||||||
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp);
|
|
||||||
lcd.createChar(LCD_STR_DEGREE[0], degree);
|
#elif defined(LCD_I2C_TYPE_PCA8574)
|
||||||
lcd.createChar(LCD_STR_THERMOMETER[0], thermometer);
|
lcd.init();
|
||||||
lcd.createChar(LCD_STR_UPLEVEL[0], uplevel);
|
lcd.backlight();
|
||||||
lcd.createChar(LCD_STR_REFRESH[0], refresh);
|
|
||||||
lcd.createChar(LCD_STR_FOLDER[0], folder);
|
#else
|
||||||
lcd.createChar(LCD_STR_FEEDRATE[0], feedrate);
|
lcd.begin(LCD_WIDTH, LCD_HEIGHT);
|
||||||
lcd.createChar(LCD_STR_CLOCK[0], clock);
|
#endif
|
||||||
lcd.clear();
|
|
||||||
}
|
lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp);
|
||||||
static void lcd_implementation_clear()
|
lcd.createChar(LCD_STR_DEGREE[0], degree);
|
||||||
{
|
lcd.createChar(LCD_STR_THERMOMETER[0], thermometer);
|
||||||
lcd.clear();
|
lcd.createChar(LCD_STR_UPLEVEL[0], uplevel);
|
||||||
}
|
lcd.createChar(LCD_STR_REFRESH[0], refresh);
|
||||||
/* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */
|
lcd.createChar(LCD_STR_FOLDER[0], folder);
|
||||||
static void lcd_printPGM(const char* str)
|
lcd.createChar(LCD_STR_FEEDRATE[0], feedrate);
|
||||||
{
|
lcd.createChar(LCD_STR_CLOCK[0], clock);
|
||||||
char c;
|
lcd.clear();
|
||||||
while((c = pgm_read_byte(str++)) != '\0')
|
}
|
||||||
{
|
static void lcd_implementation_clear()
|
||||||
lcd.write(c);
|
{
|
||||||
}
|
lcd.clear();
|
||||||
}
|
}
|
||||||
/*
|
/* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */
|
||||||
Possible status screens:
|
static void lcd_printPGM(const char* str)
|
||||||
16x2 |0123456789012345|
|
{
|
||||||
|000/000 B000/000|
|
char c;
|
||||||
|Status line.....|
|
while((c = pgm_read_byte(str++)) != '\0')
|
||||||
|
{
|
||||||
16x4 |0123456789012345|
|
lcd.write(c);
|
||||||
|000/000 B000/000|
|
}
|
||||||
|SD100% Z000.0|
|
}
|
||||||
|F100% T--:--|
|
/*
|
||||||
|Status line.....|
|
Possible status screens:
|
||||||
|
16x2 |0123456789012345|
|
||||||
20x2 |01234567890123456789|
|
|000/000 B000/000|
|
||||||
|T000/000D B000/000D |
|
|Status line.....|
|
||||||
|Status line.........|
|
|
||||||
|
16x4 |0123456789012345|
|
||||||
20x4 |01234567890123456789|
|
|000/000 B000/000|
|
||||||
|T000/000D B000/000D |
|
|SD100% Z000.0|
|
||||||
|X+000.0 Y+000.0 Z+000.0|
|
|F100% T--:--|
|
||||||
|F100% SD100% T--:--|
|
|Status line.....|
|
||||||
|Status line.........|
|
|
||||||
|
20x2 |01234567890123456789|
|
||||||
20x4 |01234567890123456789|
|
|T000/000D B000/000D |
|
||||||
|T000/000D B000/000D |
|
|Status line.........|
|
||||||
|T000/000D Z000.0|
|
|
||||||
|F100% SD100% T--:--|
|
20x4 |01234567890123456789|
|
||||||
|Status line.........|
|
|T000/000D B000/000D |
|
||||||
*/
|
|X+000.0 Y+000.0 Z+000.0|
|
||||||
static void lcd_implementation_status_screen()
|
|F100% SD100% T--:--|
|
||||||
{
|
|Status line.........|
|
||||||
int tHotend=int(degHotend(0) + 0.5);
|
|
||||||
int tTarget=int(degTargetHotend(0) + 0.5);
|
20x4 |01234567890123456789|
|
||||||
|
|T000/000D B000/000D |
|
||||||
#if LCD_WIDTH < 20
|
|T000/000D Z000.0|
|
||||||
lcd.setCursor(0, 0);
|
|F100% SD100% T--:--|
|
||||||
lcd.print(itostr3(tHotend));
|
|Status line.........|
|
||||||
lcd.print('/');
|
*/
|
||||||
lcd.print(itostr3left(tTarget));
|
static void lcd_implementation_status_screen()
|
||||||
|
{
|
||||||
# if EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
int tHotend=int(degHotend(0) + 0.5);
|
||||||
//If we have an 2nd extruder or heated bed, show that in the top right corner
|
int tTarget=int(degTargetHotend(0) + 0.5);
|
||||||
lcd.setCursor(8, 0);
|
|
||||||
# if EXTRUDERS > 1
|
#if LCD_WIDTH < 20
|
||||||
tHotend = int(degHotend(1) + 0.5);
|
lcd.setCursor(0, 0);
|
||||||
tTarget = int(degTargetHotend(1) + 0.5);
|
lcd.print(itostr3(tHotend));
|
||||||
lcd.print(LCD_STR_THERMOMETER[0]);
|
lcd.print('/');
|
||||||
# else//Heated bed
|
lcd.print(itostr3left(tTarget));
|
||||||
tHotend=int(degBed() + 0.5);
|
|
||||||
tTarget=int(degTargetBed() + 0.5);
|
# if EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
lcd.print(LCD_STR_BEDTEMP[0]);
|
//If we have an 2nd extruder or heated bed, show that in the top right corner
|
||||||
# endif
|
lcd.setCursor(8, 0);
|
||||||
lcd.print(itostr3(tHotend));
|
# if EXTRUDERS > 1
|
||||||
lcd.print('/');
|
tHotend = int(degHotend(1) + 0.5);
|
||||||
lcd.print(itostr3left(tTarget));
|
tTarget = int(degTargetHotend(1) + 0.5);
|
||||||
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
lcd.print(LCD_STR_THERMOMETER[0]);
|
||||||
|
# else//Heated bed
|
||||||
#else//LCD_WIDTH > 19
|
tHotend=int(degBed() + 0.5);
|
||||||
lcd.setCursor(0, 0);
|
tTarget=int(degTargetBed() + 0.5);
|
||||||
lcd.print(LCD_STR_THERMOMETER[0]);
|
lcd.print(LCD_STR_BEDTEMP[0]);
|
||||||
lcd.print(itostr3(tHotend));
|
# endif
|
||||||
lcd.print('/');
|
lcd.print(itostr3(tHotend));
|
||||||
lcd.print(itostr3left(tTarget));
|
lcd.print('/');
|
||||||
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
lcd.print(itostr3left(tTarget));
|
||||||
if (tTarget < 10)
|
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
lcd.print(' ');
|
|
||||||
|
#else//LCD_WIDTH > 19
|
||||||
# if EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
lcd.setCursor(0, 0);
|
||||||
//If we have an 2nd extruder or heated bed, show that in the top right corner
|
lcd.print(LCD_STR_THERMOMETER[0]);
|
||||||
lcd.setCursor(10, 0);
|
lcd.print(itostr3(tHotend));
|
||||||
# if EXTRUDERS > 1
|
lcd.print('/');
|
||||||
tHotend = int(degHotend(1) + 0.5);
|
lcd.print(itostr3left(tTarget));
|
||||||
tTarget = int(degTargetHotend(1) + 0.5);
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
lcd.print(LCD_STR_THERMOMETER[0]);
|
if (tTarget < 10)
|
||||||
# else//Heated bed
|
lcd.print(' ');
|
||||||
tHotend=int(degBed() + 0.5);
|
|
||||||
tTarget=int(degTargetBed() + 0.5);
|
# if EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
lcd.print(LCD_STR_BEDTEMP[0]);
|
//If we have an 2nd extruder or heated bed, show that in the top right corner
|
||||||
# endif
|
lcd.setCursor(10, 0);
|
||||||
lcd.print(itostr3(tHotend));
|
# if EXTRUDERS > 1
|
||||||
lcd.print('/');
|
tHotend = int(degHotend(1) + 0.5);
|
||||||
lcd.print(itostr3left(tTarget));
|
tTarget = int(degTargetHotend(1) + 0.5);
|
||||||
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
lcd.print(LCD_STR_THERMOMETER[0]);
|
||||||
if (tTarget < 10)
|
# else//Heated bed
|
||||||
lcd.print(' ');
|
tHotend=int(degBed() + 0.5);
|
||||||
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
tTarget=int(degTargetBed() + 0.5);
|
||||||
#endif//LCD_WIDTH > 19
|
lcd.print(LCD_STR_BEDTEMP[0]);
|
||||||
|
# endif
|
||||||
#if LCD_HEIGHT > 2
|
lcd.print(itostr3(tHotend));
|
||||||
//Lines 2 for 4 line LCD
|
lcd.print('/');
|
||||||
# if LCD_WIDTH < 20
|
lcd.print(itostr3left(tTarget));
|
||||||
# ifdef SDSUPPORT
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
lcd.setCursor(0, 2);
|
if (tTarget < 10)
|
||||||
lcd_printPGM(PSTR("SD"));
|
lcd.print(' ');
|
||||||
if (IS_SD_PRINTING)
|
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
lcd.print(itostr3(card.percentDone()));
|
#endif//LCD_WIDTH > 19
|
||||||
else
|
|
||||||
lcd_printPGM(PSTR("---"));
|
#if LCD_HEIGHT > 2
|
||||||
lcd.print('%');
|
//Lines 2 for 4 line LCD
|
||||||
# endif//SDSUPPORT
|
# if LCD_WIDTH < 20
|
||||||
# else//LCD_WIDTH > 19
|
# ifdef SDSUPPORT
|
||||||
# if EXTRUDERS > 1 && TEMP_SENSOR_BED != 0
|
lcd.setCursor(0, 2);
|
||||||
//If we both have a 2nd extruder and a heated bed, show the heated bed temp on the 2nd line on the left, as the first line is filled with extruder temps
|
lcd_printPGM(PSTR("SD"));
|
||||||
tHotend=int(degBed() + 0.5);
|
if (IS_SD_PRINTING)
|
||||||
tTarget=int(degTargetBed() + 0.5);
|
lcd.print(itostr3(card.percentDone()));
|
||||||
|
else
|
||||||
lcd.setCursor(0, 1);
|
lcd_printPGM(PSTR("---"));
|
||||||
lcd.print(LCD_STR_BEDTEMP[0]);
|
lcd.print('%');
|
||||||
lcd.print(itostr3(tHotend));
|
# endif//SDSUPPORT
|
||||||
lcd.print('/');
|
# else//LCD_WIDTH > 19
|
||||||
lcd.print(itostr3left(tTarget));
|
# if EXTRUDERS > 1 && TEMP_SENSOR_BED != 0
|
||||||
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
//If we both have a 2nd extruder and a heated bed, show the heated bed temp on the 2nd line on the left, as the first line is filled with extruder temps
|
||||||
if (tTarget < 10)
|
tHotend=int(degBed() + 0.5);
|
||||||
lcd.print(' ');
|
tTarget=int(degTargetBed() + 0.5);
|
||||||
# else
|
|
||||||
lcd.setCursor(0,1);
|
lcd.setCursor(0, 1);
|
||||||
lcd.print('X');
|
lcd.print(LCD_STR_BEDTEMP[0]);
|
||||||
lcd.print(ftostr3(current_position[X_AXIS]));
|
lcd.print(itostr3(tHotend));
|
||||||
lcd_printPGM(PSTR(" Y"));
|
lcd.print('/');
|
||||||
lcd.print(ftostr3(current_position[Y_AXIS]));
|
lcd.print(itostr3left(tTarget));
|
||||||
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
lcd_printPGM(PSTR(LCD_STR_DEGREE " "));
|
||||||
# endif//LCD_WIDTH > 19
|
if (tTarget < 10)
|
||||||
lcd.setCursor(LCD_WIDTH - 8, 1);
|
lcd.print(' ');
|
||||||
lcd.print('Z');
|
# else
|
||||||
lcd.print(ftostr32(current_position[Z_AXIS]));
|
lcd.setCursor(0,1);
|
||||||
#endif//LCD_HEIGHT > 2
|
lcd.print('X');
|
||||||
|
lcd.print(ftostr3(current_position[X_AXIS]));
|
||||||
#if LCD_HEIGHT > 3
|
lcd_printPGM(PSTR(" Y"));
|
||||||
lcd.setCursor(0, 2);
|
lcd.print(ftostr3(current_position[Y_AXIS]));
|
||||||
lcd.print(LCD_STR_FEEDRATE[0]);
|
# endif//EXTRUDERS > 1 || TEMP_SENSOR_BED != 0
|
||||||
lcd.print(itostr3(feedmultiply));
|
# endif//LCD_WIDTH > 19
|
||||||
lcd.print('%');
|
lcd.setCursor(LCD_WIDTH - 8, 1);
|
||||||
# if LCD_WIDTH > 19
|
lcd.print('Z');
|
||||||
# ifdef SDSUPPORT
|
lcd.print(ftostr32(current_position[Z_AXIS]));
|
||||||
lcd.setCursor(7, 2);
|
#endif//LCD_HEIGHT > 2
|
||||||
lcd_printPGM(PSTR("SD"));
|
|
||||||
if (IS_SD_PRINTING)
|
#if LCD_HEIGHT > 3
|
||||||
lcd.print(itostr3(card.percentDone()));
|
lcd.setCursor(0, 2);
|
||||||
else
|
lcd.print(LCD_STR_FEEDRATE[0]);
|
||||||
lcd_printPGM(PSTR("---"));
|
lcd.print(itostr3(feedmultiply));
|
||||||
lcd.print('%');
|
lcd.print('%');
|
||||||
# endif//SDSUPPORT
|
# if LCD_WIDTH > 19
|
||||||
# endif//LCD_WIDTH > 19
|
# ifdef SDSUPPORT
|
||||||
lcd.setCursor(LCD_WIDTH - 6, 2);
|
lcd.setCursor(7, 2);
|
||||||
lcd.print(LCD_STR_CLOCK[0]);
|
lcd_printPGM(PSTR("SD"));
|
||||||
if(starttime != 0)
|
if (IS_SD_PRINTING)
|
||||||
{
|
lcd.print(itostr3(card.percentDone()));
|
||||||
uint16_t time = millis()/60000 - starttime/60000;
|
else
|
||||||
lcd.print(itostr2(time/60));
|
lcd_printPGM(PSTR("---"));
|
||||||
lcd.print(':');
|
lcd.print('%');
|
||||||
lcd.print(itostr2(time%60));
|
# endif//SDSUPPORT
|
||||||
}else{
|
# endif//LCD_WIDTH > 19
|
||||||
lcd_printPGM(PSTR("--:--"));
|
lcd.setCursor(LCD_WIDTH - 6, 2);
|
||||||
}
|
lcd.print(LCD_STR_CLOCK[0]);
|
||||||
#endif
|
if(starttime != 0)
|
||||||
|
{
|
||||||
//Status message line on the last line
|
uint16_t time = millis()/60000 - starttime/60000;
|
||||||
lcd.setCursor(0, LCD_HEIGHT - 1);
|
lcd.print(itostr2(time/60));
|
||||||
lcd.print(lcd_status_message);
|
lcd.print(':');
|
||||||
}
|
lcd.print(itostr2(time%60));
|
||||||
static void lcd_implementation_drawmenu_generic(uint8_t row, const char* pstr, char pre_char, char post_char)
|
}else{
|
||||||
{
|
lcd_printPGM(PSTR("--:--"));
|
||||||
char c;
|
}
|
||||||
//Use all characters in narrow LCDs
|
#endif
|
||||||
#if LCD_WIDTH < 20
|
|
||||||
uint8_t n = LCD_WIDTH - 1 - 1;
|
//Status message line on the last line
|
||||||
#else
|
lcd.setCursor(0, LCD_HEIGHT - 1);
|
||||||
uint8_t n = LCD_WIDTH - 1 - 2;
|
lcd.print(lcd_status_message);
|
||||||
#endif
|
}
|
||||||
lcd.setCursor(0, row);
|
static void lcd_implementation_drawmenu_generic(uint8_t row, const char* pstr, char pre_char, char post_char)
|
||||||
lcd.print(pre_char);
|
{
|
||||||
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
char c;
|
||||||
{
|
//Use all characters in narrow LCDs
|
||||||
lcd.print(c);
|
#if LCD_WIDTH < 20
|
||||||
pstr++;
|
uint8_t n = LCD_WIDTH - 1 - 1;
|
||||||
n--;
|
#else
|
||||||
}
|
uint8_t n = LCD_WIDTH - 1 - 2;
|
||||||
while(n--)
|
#endif
|
||||||
lcd.print(' ');
|
lcd.setCursor(0, row);
|
||||||
lcd.print(post_char);
|
lcd.print(pre_char);
|
||||||
lcd.print(' ');
|
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
||||||
}
|
{
|
||||||
static void lcd_implementation_drawmenu_setting_edit_generic(uint8_t row, const char* pstr, char pre_char, char* data)
|
lcd.print(c);
|
||||||
{
|
pstr++;
|
||||||
char c;
|
n--;
|
||||||
//Use all characters in narrow LCDs
|
}
|
||||||
#if LCD_WIDTH < 20
|
while(n--)
|
||||||
uint8_t n = LCD_WIDTH - 1 - 1 - strlen(data);
|
lcd.print(' ');
|
||||||
#else
|
lcd.print(post_char);
|
||||||
uint8_t n = LCD_WIDTH - 1 - 2 - strlen(data);
|
lcd.print(' ');
|
||||||
#endif
|
}
|
||||||
lcd.setCursor(0, row);
|
static void lcd_implementation_drawmenu_setting_edit_generic(uint8_t row, const char* pstr, char pre_char, char* data)
|
||||||
lcd.print(pre_char);
|
{
|
||||||
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
char c;
|
||||||
{
|
//Use all characters in narrow LCDs
|
||||||
lcd.print(c);
|
#if LCD_WIDTH < 20
|
||||||
pstr++;
|
uint8_t n = LCD_WIDTH - 1 - 1 - strlen(data);
|
||||||
n--;
|
#else
|
||||||
}
|
uint8_t n = LCD_WIDTH - 1 - 2 - strlen(data);
|
||||||
lcd.print(':');
|
#endif
|
||||||
while(n--)
|
lcd.setCursor(0, row);
|
||||||
lcd.print(' ');
|
lcd.print(pre_char);
|
||||||
lcd.print(data);
|
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
||||||
}
|
{
|
||||||
static void lcd_implementation_drawmenu_setting_edit_generic_P(uint8_t row, const char* pstr, char pre_char, const char* data)
|
lcd.print(c);
|
||||||
{
|
pstr++;
|
||||||
char c;
|
n--;
|
||||||
//Use all characters in narrow LCDs
|
}
|
||||||
#if LCD_WIDTH < 20
|
lcd.print(':');
|
||||||
uint8_t n = LCD_WIDTH - 1 - 1 - strlen_P(data);
|
while(n--)
|
||||||
#else
|
lcd.print(' ');
|
||||||
uint8_t n = LCD_WIDTH - 1 - 2 - strlen_P(data);
|
lcd.print(data);
|
||||||
#endif
|
}
|
||||||
lcd.setCursor(0, row);
|
static void lcd_implementation_drawmenu_setting_edit_generic_P(uint8_t row, const char* pstr, char pre_char, const char* data)
|
||||||
lcd.print(pre_char);
|
{
|
||||||
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
char c;
|
||||||
{
|
//Use all characters in narrow LCDs
|
||||||
lcd.print(c);
|
#if LCD_WIDTH < 20
|
||||||
pstr++;
|
uint8_t n = LCD_WIDTH - 1 - 1 - strlen_P(data);
|
||||||
n--;
|
#else
|
||||||
}
|
uint8_t n = LCD_WIDTH - 1 - 2 - strlen_P(data);
|
||||||
lcd.print(':');
|
#endif
|
||||||
while(n--)
|
lcd.setCursor(0, row);
|
||||||
lcd.print(' ');
|
lcd.print(pre_char);
|
||||||
lcd_printPGM(data);
|
while( ((c = pgm_read_byte(pstr)) != '\0') && (n>0) )
|
||||||
}
|
{
|
||||||
#define lcd_implementation_drawmenu_setting_edit_int3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data)))
|
lcd.print(c);
|
||||||
#define lcd_implementation_drawmenu_setting_edit_int3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data)))
|
pstr++;
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data)))
|
n--;
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data)))
|
}
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float32_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data)))
|
lcd.print(':');
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float32(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data)))
|
while(n--)
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
lcd.print(' ');
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
lcd_printPGM(data);
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float52_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data)))
|
}
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float52(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_int3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float51_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_int3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_float51(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_float3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_long5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_float3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_long5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_float32_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_bool_selected(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
#define lcd_implementation_drawmenu_setting_edit_float32(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_bool(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
#define lcd_implementation_drawmenu_setting_edit_float5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_float5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
||||||
//Add version for callback functions
|
#define lcd_implementation_drawmenu_setting_edit_float52_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_int3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_float52(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_int3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_float51_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_float51(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_long5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float32_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_long5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float32(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_bool_selected(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_bool(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float52_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data)))
|
//Add version for callback functions
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float52(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_callback_int3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float51_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_callback_int3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_float51(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_callback_float3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_long5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_callback_float3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_long5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
#define lcd_implementation_drawmenu_setting_edit_callback_float32_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_bool_selected(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
#define lcd_implementation_drawmenu_setting_edit_callback_float32(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data)))
|
||||||
#define lcd_implementation_drawmenu_setting_edit_callback_bool(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
#define lcd_implementation_drawmenu_setting_edit_callback_float5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_callback_float5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
||||||
|
#define lcd_implementation_drawmenu_setting_edit_callback_float52_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data)))
|
||||||
void lcd_implementation_drawedit(const char* pstr, char* value)
|
#define lcd_implementation_drawmenu_setting_edit_callback_float52(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data)))
|
||||||
{
|
#define lcd_implementation_drawmenu_setting_edit_callback_float51_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data)))
|
||||||
lcd.setCursor(1, 1);
|
#define lcd_implementation_drawmenu_setting_edit_callback_float51(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data)))
|
||||||
lcd_printPGM(pstr);
|
#define lcd_implementation_drawmenu_setting_edit_callback_long5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data)))
|
||||||
lcd.print(':');
|
#define lcd_implementation_drawmenu_setting_edit_callback_long5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data)))
|
||||||
#if LCD_WIDTH < 20
|
#define lcd_implementation_drawmenu_setting_edit_callback_bool_selected(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
||||||
lcd.setCursor(LCD_WIDTH - strlen(value), 1);
|
#define lcd_implementation_drawmenu_setting_edit_callback_bool(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF))
|
||||||
#else
|
|
||||||
lcd.setCursor(LCD_WIDTH -1 - strlen(value), 1);
|
|
||||||
#endif
|
void lcd_implementation_drawedit(const char* pstr, char* value)
|
||||||
lcd.print(value);
|
{
|
||||||
}
|
lcd.setCursor(1, 1);
|
||||||
static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
lcd_printPGM(pstr);
|
||||||
{
|
lcd.print(':');
|
||||||
char c;
|
#if LCD_WIDTH < 20
|
||||||
uint8_t n = LCD_WIDTH - 1;
|
lcd.setCursor(LCD_WIDTH - strlen(value), 1);
|
||||||
lcd.setCursor(0, row);
|
#else
|
||||||
lcd.print('>');
|
lcd.setCursor(LCD_WIDTH -1 - strlen(value), 1);
|
||||||
if (longFilename[0] != '\0')
|
#endif
|
||||||
{
|
lcd.print(value);
|
||||||
filename = longFilename;
|
}
|
||||||
longFilename[LCD_WIDTH-1] = '\0';
|
static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
}
|
{
|
||||||
while( ((c = *filename) != '\0') && (n>0) )
|
char c;
|
||||||
{
|
uint8_t n = LCD_WIDTH - 1;
|
||||||
lcd.print(c);
|
lcd.setCursor(0, row);
|
||||||
filename++;
|
lcd.print('>');
|
||||||
n--;
|
if (longFilename[0] != '\0')
|
||||||
}
|
{
|
||||||
while(n--)
|
filename = longFilename;
|
||||||
lcd.print(' ');
|
longFilename[LCD_WIDTH-1] = '\0';
|
||||||
}
|
}
|
||||||
static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
char c;
|
lcd.print(c);
|
||||||
uint8_t n = LCD_WIDTH - 1;
|
filename++;
|
||||||
lcd.setCursor(0, row);
|
n--;
|
||||||
lcd.print(' ');
|
}
|
||||||
if (longFilename[0] != '\0')
|
while(n--)
|
||||||
{
|
lcd.print(' ');
|
||||||
filename = longFilename;
|
}
|
||||||
longFilename[LCD_WIDTH-1] = '\0';
|
static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
}
|
{
|
||||||
while( ((c = *filename) != '\0') && (n>0) )
|
char c;
|
||||||
{
|
uint8_t n = LCD_WIDTH - 1;
|
||||||
lcd.print(c);
|
lcd.setCursor(0, row);
|
||||||
filename++;
|
lcd.print(' ');
|
||||||
n--;
|
if (longFilename[0] != '\0')
|
||||||
}
|
{
|
||||||
while(n--)
|
filename = longFilename;
|
||||||
lcd.print(' ');
|
longFilename[LCD_WIDTH-1] = '\0';
|
||||||
}
|
}
|
||||||
static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
char c;
|
lcd.print(c);
|
||||||
uint8_t n = LCD_WIDTH - 2;
|
filename++;
|
||||||
lcd.setCursor(0, row);
|
n--;
|
||||||
lcd.print('>');
|
}
|
||||||
lcd.print(LCD_STR_FOLDER[0]);
|
while(n--)
|
||||||
if (longFilename[0] != '\0')
|
lcd.print(' ');
|
||||||
{
|
}
|
||||||
filename = longFilename;
|
static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
longFilename[LCD_WIDTH-2] = '\0';
|
{
|
||||||
}
|
char c;
|
||||||
while( ((c = *filename) != '\0') && (n>0) )
|
uint8_t n = LCD_WIDTH - 2;
|
||||||
{
|
lcd.setCursor(0, row);
|
||||||
lcd.print(c);
|
lcd.print('>');
|
||||||
filename++;
|
lcd.print(LCD_STR_FOLDER[0]);
|
||||||
n--;
|
if (longFilename[0] != '\0')
|
||||||
}
|
{
|
||||||
while(n--)
|
filename = longFilename;
|
||||||
lcd.print(' ');
|
longFilename[LCD_WIDTH-2] = '\0';
|
||||||
}
|
}
|
||||||
static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
{
|
{
|
||||||
char c;
|
lcd.print(c);
|
||||||
uint8_t n = LCD_WIDTH - 2;
|
filename++;
|
||||||
lcd.setCursor(0, row);
|
n--;
|
||||||
lcd.print(' ');
|
}
|
||||||
lcd.print(LCD_STR_FOLDER[0]);
|
while(n--)
|
||||||
if (longFilename[0] != '\0')
|
lcd.print(' ');
|
||||||
{
|
}
|
||||||
filename = longFilename;
|
static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, const char* filename, char* longFilename)
|
||||||
longFilename[LCD_WIDTH-2] = '\0';
|
{
|
||||||
}
|
char c;
|
||||||
while( ((c = *filename) != '\0') && (n>0) )
|
uint8_t n = LCD_WIDTH - 2;
|
||||||
{
|
lcd.setCursor(0, row);
|
||||||
lcd.print(c);
|
lcd.print(' ');
|
||||||
filename++;
|
lcd.print(LCD_STR_FOLDER[0]);
|
||||||
n--;
|
if (longFilename[0] != '\0')
|
||||||
}
|
{
|
||||||
while(n--)
|
filename = longFilename;
|
||||||
lcd.print(' ');
|
longFilename[LCD_WIDTH-2] = '\0';
|
||||||
}
|
}
|
||||||
#define lcd_implementation_drawmenu_back_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0])
|
while( ((c = *filename) != '\0') && (n>0) )
|
||||||
#define lcd_implementation_drawmenu_back(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_UPLEVEL[0])
|
{
|
||||||
#define lcd_implementation_drawmenu_submenu_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', LCD_STR_ARROW_RIGHT[0])
|
lcd.print(c);
|
||||||
#define lcd_implementation_drawmenu_submenu(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_ARROW_RIGHT[0])
|
filename++;
|
||||||
#define lcd_implementation_drawmenu_gcode_selected(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ')
|
n--;
|
||||||
#define lcd_implementation_drawmenu_gcode(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ')
|
}
|
||||||
#define lcd_implementation_drawmenu_function_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ')
|
while(n--)
|
||||||
#define lcd_implementation_drawmenu_function(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ')
|
lcd.print(' ');
|
||||||
|
}
|
||||||
static void lcd_implementation_quick_feedback()
|
#define lcd_implementation_drawmenu_back_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0])
|
||||||
{
|
#define lcd_implementation_drawmenu_back(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_UPLEVEL[0])
|
||||||
#ifdef LCD_USE_I2C_BUZZER
|
#define lcd_implementation_drawmenu_submenu_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', LCD_STR_ARROW_RIGHT[0])
|
||||||
lcd.buzz(60,1000/6);
|
#define lcd_implementation_drawmenu_submenu(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_ARROW_RIGHT[0])
|
||||||
#elif defined(BEEPER) && BEEPER > -1
|
#define lcd_implementation_drawmenu_gcode_selected(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ')
|
||||||
SET_OUTPUT(BEEPER);
|
#define lcd_implementation_drawmenu_gcode(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ')
|
||||||
for(int8_t i=0;i<10;i++)
|
#define lcd_implementation_drawmenu_function_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ')
|
||||||
{
|
#define lcd_implementation_drawmenu_function(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ')
|
||||||
WRITE(BEEPER,HIGH);
|
|
||||||
delay(3);
|
static void lcd_implementation_quick_feedback()
|
||||||
WRITE(BEEPER,LOW);
|
{
|
||||||
delay(3);
|
#ifdef LCD_USE_I2C_BUZZER
|
||||||
}
|
lcd.buzz(60,1000/6);
|
||||||
#endif
|
#elif defined(BEEPER) && BEEPER > -1
|
||||||
}
|
SET_OUTPUT(BEEPER);
|
||||||
|
for(int8_t i=0;i<10;i++)
|
||||||
#ifdef LCD_HAS_STATUS_INDICATORS
|
{
|
||||||
static void lcd_implementation_update_indicators()
|
WRITE(BEEPER,HIGH);
|
||||||
{
|
delayMicroseconds(100);
|
||||||
#if defined(LCD_I2C_PANELOLU2) || defined(LCD_I2C_VIKI)
|
WRITE(BEEPER,LOW);
|
||||||
//set the LEDS - referred to as backlights by the LiquidTWI2 library
|
delayMicroseconds(100);
|
||||||
static uint8_t ledsprev = 0;
|
}
|
||||||
uint8_t leds = 0;
|
#endif
|
||||||
if (target_temperature_bed > 0) leds |= LED_A;
|
}
|
||||||
if (target_temperature[0] > 0) leds |= LED_B;
|
|
||||||
if (fanSpeed) leds |= LED_C;
|
#ifdef LCD_HAS_STATUS_INDICATORS
|
||||||
#if EXTRUDERS > 1
|
static void lcd_implementation_update_indicators()
|
||||||
if (target_temperature[1] > 0) leds |= LED_C;
|
{
|
||||||
#endif
|
#if defined(LCD_I2C_PANELOLU2) || defined(LCD_I2C_VIKI)
|
||||||
if (leds != ledsprev) {
|
//set the LEDS - referred to as backlights by the LiquidTWI2 library
|
||||||
lcd.setBacklight(leds);
|
static uint8_t ledsprev = 0;
|
||||||
ledsprev = leds;
|
uint8_t leds = 0;
|
||||||
}
|
if (target_temperature_bed > 0) leds |= LED_A;
|
||||||
#endif
|
if (target_temperature[0] > 0) leds |= LED_B;
|
||||||
}
|
if (fanSpeed) leds |= LED_C;
|
||||||
#endif
|
#if EXTRUDERS > 1
|
||||||
|
if (target_temperature[1] > 0) leds |= LED_C;
|
||||||
#ifdef LCD_HAS_SLOW_BUTTONS
|
#endif
|
||||||
static uint8_t lcd_implementation_read_slow_buttons()
|
if (leds != ledsprev) {
|
||||||
{
|
lcd.setBacklight(leds);
|
||||||
#ifdef LCD_I2C_TYPE_MCP23017
|
ledsprev = leds;
|
||||||
// Reading these buttons this is likely to be too slow to call inside interrupt context
|
}
|
||||||
// so they are called during normal lcd_update
|
#endif
|
||||||
return lcd.readButtons() << B_I2C_BTN_OFFSET;
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
|
||||||
#endif
|
#ifdef LCD_HAS_SLOW_BUTTONS
|
||||||
|
static uint8_t lcd_implementation_read_slow_buttons()
|
||||||
#endif//ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
{
|
||||||
|
#ifdef LCD_I2C_TYPE_MCP23017
|
||||||
|
// Reading these buttons this is likely to be too slow to call inside interrupt context
|
||||||
|
// so they are called during normal lcd_update
|
||||||
|
return lcd.readButtons() << B_I2C_BTN_OFFSET;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif//ULTRA_LCD_IMPLEMENTATION_HITACHI_HD44780_H
|
||||||
|
|
131
Marlin/ultralcd_st7920_u8glib_rrd.h
Normal file
131
Marlin/ultralcd_st7920_u8glib_rrd.h
Normal file
|
@ -0,0 +1,131 @@
|
||||||
|
#ifndef ULCDST7920_H
|
||||||
|
#define ULCDST7920_H
|
||||||
|
|
||||||
|
#include "Marlin.h"
|
||||||
|
|
||||||
|
#ifdef U8GLIB_ST7920
|
||||||
|
|
||||||
|
//set optimization so ARDUINO optimizes this file
|
||||||
|
#pragma GCC optimize (3)
|
||||||
|
|
||||||
|
#define ST7920_CLK_PIN LCD_PINS_D4
|
||||||
|
#define ST7920_DAT_PIN LCD_PINS_ENABLE
|
||||||
|
#define ST7920_CS_PIN LCD_PINS_RS
|
||||||
|
|
||||||
|
//#define PAGE_HEIGHT 8 //128 byte frambuffer
|
||||||
|
//#define PAGE_HEIGHT 16 //256 byte frambuffer
|
||||||
|
#define PAGE_HEIGHT 32 //512 byte framebuffer
|
||||||
|
|
||||||
|
#define WIDTH 128
|
||||||
|
#define HEIGHT 64
|
||||||
|
|
||||||
|
#include <U8glib.h>
|
||||||
|
|
||||||
|
static void ST7920_SWSPI_SND_8BIT(uint8_t val)
|
||||||
|
{
|
||||||
|
uint8_t i;
|
||||||
|
for( i=0; i<8; i++ )
|
||||||
|
{
|
||||||
|
WRITE(ST7920_CLK_PIN,0);
|
||||||
|
WRITE(ST7920_DAT_PIN,val&0x80);
|
||||||
|
val<<=1;
|
||||||
|
WRITE(ST7920_CLK_PIN,1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#define ST7920_CS() {WRITE(ST7920_CS_PIN,1);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_NCS() {WRITE(ST7920_CS_PIN,0);}
|
||||||
|
#define ST7920_SET_CMD() {ST7920_SWSPI_SND_8BIT(0xf8);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_SET_DAT() {ST7920_SWSPI_SND_8BIT(0xfa);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_WRITE_BYTE(a) {ST7920_SWSPI_SND_8BIT((a)&0xf0);ST7920_SWSPI_SND_8BIT((a)<<4);u8g_10MicroDelay();}
|
||||||
|
#define ST7920_WRITE_BYTES(p,l) {uint8_t i;for(i=0;i<l;i++){ST7920_SWSPI_SND_8BIT(*p&0xf0);ST7920_SWSPI_SND_8BIT(*p<<4);p++;}u8g_10MicroDelay();}
|
||||||
|
|
||||||
|
uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void *arg)
|
||||||
|
{
|
||||||
|
uint8_t i,y;
|
||||||
|
switch(msg)
|
||||||
|
{
|
||||||
|
case U8G_DEV_MSG_INIT:
|
||||||
|
{
|
||||||
|
SET_OUTPUT(ST7920_CS_PIN);
|
||||||
|
WRITE(ST7920_CS_PIN,0);
|
||||||
|
SET_OUTPUT(ST7920_DAT_PIN);
|
||||||
|
WRITE(ST7920_DAT_PIN,0);
|
||||||
|
SET_OUTPUT(ST7920_CLK_PIN);
|
||||||
|
WRITE(ST7920_CLK_PIN,1);
|
||||||
|
|
||||||
|
ST7920_CS();
|
||||||
|
u8g_Delay(90); //initial delay for boot up
|
||||||
|
ST7920_SET_CMD();
|
||||||
|
ST7920_WRITE_BYTE(0x08); //display off, cursor+blink off
|
||||||
|
ST7920_WRITE_BYTE(0x01); //clear CGRAM ram
|
||||||
|
u8g_Delay(10); //delay for cgram clear
|
||||||
|
ST7920_WRITE_BYTE(0x3E); //extended mode + gdram active
|
||||||
|
for(y=0;y<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
|
||||||
|
ST7920_WRITE_BYTE(0);
|
||||||
|
ST7920_SET_CMD();
|
||||||
|
}
|
||||||
|
ST7920_WRITE_BYTE(0x0C); //display on, cursor+blink off
|
||||||
|
ST7920_NCS();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case U8G_DEV_MSG_STOP:
|
||||||
|
break;
|
||||||
|
case U8G_DEV_MSG_PAGE_NEXT:
|
||||||
|
{
|
||||||
|
uint8_t *ptr;
|
||||||
|
u8g_pb_t *pb = (u8g_pb_t *)(dev->dev_mem);
|
||||||
|
y = pb->p.page_y0;
|
||||||
|
ptr = (uint8_t*)pb->buf;
|
||||||
|
|
||||||
|
ST7920_CS();
|
||||||
|
for( i = 0; i < PAGE_HEIGHT; i ++ )
|
||||||
|
{
|
||||||
|
ST7920_SET_CMD();
|
||||||
|
if ( y < 32 )
|
||||||
|
{
|
||||||
|
ST7920_WRITE_BYTE(0x80 | y); //y
|
||||||
|
ST7920_WRITE_BYTE(0x80); //x=0
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
ST7920_WRITE_BYTE(0x80 | (y-32)); //y
|
||||||
|
ST7920_WRITE_BYTE(0x80 | 8); //x=64
|
||||||
|
}
|
||||||
|
|
||||||
|
ST7920_SET_DAT();
|
||||||
|
ST7920_WRITE_BYTES(ptr,WIDTH/8); //ptr is incremented inside of macro
|
||||||
|
y++;
|
||||||
|
}
|
||||||
|
ST7920_NCS();
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#if PAGE_HEIGHT == 8
|
||||||
|
return u8g_dev_pb8h1_base_fn(u8g, dev, msg, arg);
|
||||||
|
#elif PAGE_HEIGHT == 16
|
||||||
|
return u8g_dev_pb16h1_base_fn(u8g, dev, msg, arg);
|
||||||
|
#else
|
||||||
|
return u8g_dev_pb32h1_base_fn(u8g, dev, msg, arg);
|
||||||
|
#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};
|
||||||
|
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
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
U8GLIB_ST7920_128X64_RRD(uint8_t dummy) : U8GLIB(&u8g_dev_st7920_128x64_rrd_sw_spi) {}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
#endif //U8GLIB_ST7920
|
||||||
|
#endif //ULCDST7920_H
|
479
README.md
479
README.md
|
@ -1,227 +1,252 @@
|
||||||
==========================
|
==========================
|
||||||
Marlin 3D Printer Firmware
|
Marlin 3D Printer Firmware
|
||||||
==========================
|
==========================
|
||||||
|
|
||||||
Notes:
|
[![Flattr this git repo](http://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=ErikZalm&url=https://github.com/ErikZalm/Marlin&title=Marlin&language=&tags=github&category=software)
|
||||||
-----
|
|
||||||
|
Quick Information
|
||||||
The configuration is now split in two files:
|
===================
|
||||||
Configuration.h for the normal settings
|
This RepRap firmware is a mashup between <a href="https://github.com/kliment/Sprinter">Sprinter</a>, <a href="https://github.com/simen/grbl/tree">grbl</a> and many original parts.
|
||||||
Configuration_adv.h for the advanced settings
|
|
||||||
|
Derived from Sprinter and Grbl by Erik van der Zalm.
|
||||||
Gen7T is not supported.
|
Sprinters lead developers are Kliment and caru.
|
||||||
|
Grbls lead developer is Simen Svale Skogsrud. Sonney Jeon (Chamnit) improved some parts of grbl
|
||||||
Quick Information
|
A fork by bkubicek for the Ultimaker was merged, and further development was aided by him.
|
||||||
===================
|
Some features have been added by:
|
||||||
This RepRap firmware is a mashup between <a href="https://github.com/kliment/Sprinter">Sprinter</a>, <a href="https://github.com/simen/grbl/tree">grbl</a> and many original parts.
|
Lampmaker, Bradley Feldman, and others...
|
||||||
|
|
||||||
Derived from Sprinter and Grbl by Erik van der Zalm.
|
|
||||||
Sprinters lead developers are Kliment and caru.
|
Features:
|
||||||
Grbls lead developer is Simen Svale Skogsrud. Sonney Jeon (Chamnit) improved some parts of grbl
|
|
||||||
A fork by bkubicek for the Ultimaker was merged, and further development was aided by him.
|
* Interrupt based movement with real linear acceleration
|
||||||
Some features have been added by:
|
* High steprate
|
||||||
Lampmaker, Bradley Feldman, and others...
|
* Look ahead (Keep the speed high when possible. High cornering speed)
|
||||||
|
* Interrupt based temperature protection
|
||||||
|
* preliminary support for Matthew Roberts advance algorithm
|
||||||
Features:
|
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
||||||
|
* Full endstop support
|
||||||
* Interrupt based movement with real linear acceleration
|
* SD Card support
|
||||||
* High steprate
|
* SD Card folders (works in pronterface)
|
||||||
* Look ahead (Keep the speed high when possible. High cornering speed)
|
* SD Card autostart support
|
||||||
* Interrupt based temperature protection
|
* LCD support (ideally 20x4)
|
||||||
* preliminary support for Matthew Roberts advance algorithm
|
* LCD menu system for autonomous SD card printing, controlled by an click-encoder.
|
||||||
For more info see: http://reprap.org/pipermail/reprap-dev/2011-May/003323.html
|
* EEPROM storage of e.g. max-velocity, max-acceleration, and similar variables
|
||||||
* Full endstop support
|
* many small but handy things originating from bkubicek's fork.
|
||||||
* SD Card support
|
* Arc support
|
||||||
* SD Card folders (works in pronterface)
|
* Temperature oversampling
|
||||||
* SD Card autostart support
|
* Dynamic Temperature setpointing aka "AutoTemp"
|
||||||
* LCD support (ideally 20x4)
|
* Support for QTMarlin, a very beta GUI for PID-tuning and velocity-acceleration testing. https://github.com/bkubicek/QTMarlin
|
||||||
* LCD menu system for autonomous SD card printing, controlled by an click-encoder.
|
* Endstop trigger reporting to the host software.
|
||||||
* EEPROM storage of e.g. max-velocity, max-acceleration, and similar variables
|
* Updated sdcardlib
|
||||||
* many small but handy things originating from bkubicek's fork.
|
* Heater power reporting. Useful for PID monitoring.
|
||||||
* Arc support
|
* PID tuning
|
||||||
* Temperature oversampling
|
* CoreXY kinematics (www.corexy.com/theory.html)
|
||||||
* Dynamic Temperature setpointing aka "AutoTemp"
|
* Delta kinematics
|
||||||
* Support for QTMarlin, a very beta GUI for PID-tuning and velocity-acceleration testing. https://github.com/bkubicek/QTMarlin
|
* Dual X-carriage support for multiple extruder systems
|
||||||
* Endstop trigger reporting to the host software.
|
* Configurable serial port to support connection of wireless adaptors.
|
||||||
* Updated sdcardlib
|
* Automatic operation of extruder/cold-end cooling fans based on nozzle temperature
|
||||||
* Heater power reporting. Useful for PID monitoring.
|
* RC Servo Support, specify angle or duration for continuous rotation servos.
|
||||||
* PID tuning
|
|
||||||
* CoreXY kinematics (www.corexy.com/theory.html)
|
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
|
||||||
* Configurable serial port to support connection of wireless adaptors.
|
|
||||||
* Automatic operation of extruder/cold-end cooling fans based on nozzle temperature
|
|
||||||
|
Differences and additions to the already good Sprinter firmware:
|
||||||
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
|
================================================================
|
||||||
|
|
||||||
|
*Look-ahead:*
|
||||||
Differences and additions to the already good Sprinter firmware:
|
|
||||||
================================================================
|
Marlin has look-ahead. While sprinter has to break and re-accelerate at each corner,
|
||||||
|
lookahead will only decelerate and accelerate to a velocity,
|
||||||
*Look-ahead:*
|
so that the change in vectorial velocity magnitude is less than the xy_jerk_velocity.
|
||||||
|
This is only possible, if some future moves are already processed, hence the name.
|
||||||
Marlin has look-ahead. While sprinter has to break and re-accelerate at each corner,
|
It leads to less over-deposition at corners, especially at flat angles.
|
||||||
lookahead will only decelerate and accelerate to a velocity,
|
|
||||||
so that the change in vectorial velocity magnitude is less than the xy_jerk_velocity.
|
*Arc support:*
|
||||||
This is only possible, if some future moves are already processed, hence the name.
|
|
||||||
It leads to less over-deposition at corners, especially at flat angles.
|
Slic3r can find curves that, although broken into segments, were ment to describe an arc.
|
||||||
|
Marlin is able to print those arcs. The advantage is the firmware can choose the resolution,
|
||||||
*Arc support:*
|
and can perform the arc with nearly constant velocity, resulting in a nice finish.
|
||||||
|
Also, less serial communication is needed.
|
||||||
Slic3r can find curves that, although broken into segments, were ment to describe an arc.
|
|
||||||
Marlin is able to print those arcs. The advantage is the firmware can choose the resolution,
|
*Temperature Oversampling:*
|
||||||
and can perform the arc with nearly constant velocity, resulting in a nice finish.
|
|
||||||
Also, less serial communication is needed.
|
To reduce noise and make the PID-differential term more useful, 16 ADC conversion results are averaged.
|
||||||
|
|
||||||
*Temperature Oversampling:*
|
*AutoTemp:*
|
||||||
|
|
||||||
To reduce noise and make the PID-differential term more useful, 16 ADC conversion results are averaged.
|
If your gcode contains a wide spread of extruder velocities, or you realtime change the building speed, the temperature should be changed accordingly.
|
||||||
|
Usually, higher speed requires higher temperature.
|
||||||
*AutoTemp:*
|
This can now be performed by the AutoTemp function
|
||||||
|
By calling M109 S<mintemp> T<maxtemp> F<factor> you enter the autotemp mode.
|
||||||
If your gcode contains a wide spread of extruder velocities, or you realtime change the building speed, the temperature should be changed accordingly.
|
|
||||||
Usually, higher speed requires higher temperature.
|
You can leave it by calling M109 without any F.
|
||||||
This can now be performed by the AutoTemp function
|
If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec].
|
||||||
By calling M109 S<mintemp> T<maxtemp> F<factor> you enter the autotemp mode.
|
The wanted temperature then will be set to t=tempmin+factor*maxerate, while being limited between tempmin and tempmax.
|
||||||
|
If the target temperature is set manually or by gcode to a value less then tempmin, it will be kept without change.
|
||||||
You can leave it by calling M109 without any F.
|
Ideally, your gcode can be completely free of temperature controls, apart from a M109 S T F in the start.gcode, and a M109 S0 in the end.gcode.
|
||||||
If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec].
|
|
||||||
The wanted temperature then will be set to t=tempmin+factor*maxerate, while being limited between tempmin and tempmax.
|
*EEPROM:*
|
||||||
If the target temperature is set manually or by gcode to a value less then tempmin, it will be kept without change.
|
|
||||||
Ideally, your gcode can be completely free of temperature controls, apart from a M109 S T F in the start.gcode, and a M109 S0 in the end.gcode.
|
If you know your PID values, the acceleration and max-velocities of your unique machine, you can set them, and finally store them in the EEPROM.
|
||||||
|
After each reboot, it will magically load them from EEPROM, independent what your Configuration.h says.
|
||||||
*EEPROM:*
|
|
||||||
|
*LCD Menu:*
|
||||||
If you know your PID values, the acceleration and max-velocities of your unique machine, you can set them, and finally store them in the EEPROM.
|
|
||||||
After each reboot, it will magically load them from EEPROM, independent what your Configuration.h says.
|
If your hardware supports it, you can build yourself a LCD-CardReader+Click+encoder combination. It will enable you to realtime tune temperatures,
|
||||||
|
accelerations, velocities, flow rates, select and print files from the SD card, preheat, disable the steppers, and do other fancy stuff.
|
||||||
*LCD Menu:*
|
One working hardware is documented here: http://www.thingiverse.com/thing:12663
|
||||||
|
Also, with just a 20x4 or 16x2 display, useful data is shown.
|
||||||
If your hardware supports it, you can build yourself a LCD-CardReader+Click+encoder combination. It will enable you to realtime tune temperatures,
|
|
||||||
accelerations, velocities, flow rates, select and print files from the SD card, preheat, disable the steppers, and do other fancy stuff.
|
*SD card folders:*
|
||||||
One working hardware is documented here: http://www.thingiverse.com/thing:12663
|
|
||||||
Also, with just a 20x4 or 16x2 display, useful data is shown.
|
If you have an SD card reader attached to your controller, also folders work now. Listing the files in pronterface will show "/path/subpath/file.g".
|
||||||
|
You can write to file in a subfolder by specifying a similar text using small letters in the path.
|
||||||
*SD card folders:*
|
Also, backup copies of various operating systems are hidden, as well as files not ending with ".g".
|
||||||
|
|
||||||
If you have an SD card reader attached to your controller, also folders work now. Listing the files in pronterface will show "/path/subpath/file.g".
|
*SD card folders:*
|
||||||
You can write to file in a subfolder by specifying a similar text using small letters in the path.
|
|
||||||
Also, backup copies of various operating systems are hidden, as well as files not ending with ".g".
|
If you place a file auto[0-9].g into the root of the sd card, it will be automatically executed if you boot the printer. The same file will be executed by selecting "Autostart" from the menu.
|
||||||
|
First *0 will be performed, than *1 and so on. That way, you can heat up or even print automatically without user interaction.
|
||||||
*SD card folders:*
|
|
||||||
|
*Endstop trigger reporting:*
|
||||||
If you place a file auto[0-9].g into the root of the sd card, it will be automatically executed if you boot the printer. The same file will be executed by selecting "Autostart" from the menu.
|
|
||||||
First *0 will be performed, than *1 and so on. That way, you can heat up or even print automatically without user interaction.
|
If an endstop is hit while moving towards the endstop, the location at which the firmware thinks that the endstop was triggered is outputed on the serial port.
|
||||||
|
This is useful, because the user gets a warning message.
|
||||||
*Endstop trigger reporting:*
|
However, also tools like QTMarlin can use this for finding acceptable combinations of velocity+acceleration.
|
||||||
|
|
||||||
If an endstop is hit while moving towards the endstop, the location at which the firmware thinks that the endstop was triggered is outputed on the serial port.
|
*Coding paradigm:*
|
||||||
This is useful, because the user gets a warning message.
|
|
||||||
However, also tools like QTMarlin can use this for finding acceptable combinations of velocity+acceleration.
|
Not relevant from a user side, but Marlin was split into thematic junks, and has tried to partially enforced private variables.
|
||||||
|
This is intended to make it clearer, what interacts which what, and leads to a higher level of modularization.
|
||||||
*Coding paradigm:*
|
We think that this is a useful prestep for porting this firmware to e.g. an ARM platform in the future.
|
||||||
|
A lot of RAM (with enabled LCD ~2200 bytes) was saved by storing char []="some message" in Program memory.
|
||||||
Not relevant from a user side, but Marlin was split into thematic junks, and has tried to partially enforced private variables.
|
In the serial communication, a #define based level of abstraction was enforced, so that it is clear that
|
||||||
This is intended to make it clearer, what interacts which what, and leads to a higher level of modularization.
|
some transfer is information (usually beginning with "echo:"), an error "error:", or just normal protocol,
|
||||||
We think that this is a useful prestep for porting this firmware to e.g. an ARM platform in the future.
|
necessary for backwards compatibility.
|
||||||
A lot of RAM (with enabled LCD ~2200 bytes) was saved by storing char []="some message" in Program memory.
|
|
||||||
In the serial communication, a #define based level of abstraction was enforced, so that it is clear that
|
*Interrupt based temperature measurements:*
|
||||||
some transfer is information (usually beginning with "echo:"), an error "error:", or just normal protocol,
|
|
||||||
necessary for backwards compatibility.
|
An interrupt is used to manage ADC conversions, and enforce checking for critical temperatures.
|
||||||
|
This leads to less blocking in the heater management routine.
|
||||||
*Interrupt based temperature measurements:*
|
|
||||||
|
Implemented G Codes:
|
||||||
An interrupt is used to manage ADC conversions, and enforce checking for critical temperatures.
|
====================
|
||||||
This leads to less blocking in the heater management routine.
|
|
||||||
|
* G0 -> G1
|
||||||
|
* G1 - Coordinated Movement X Y Z E
|
||||||
Non-standard M-Codes, different to an old version of sprinter:
|
* G2 - CW ARC
|
||||||
==============================================================
|
* G3 - CCW ARC
|
||||||
Movement:
|
* G4 - Dwell S<seconds> or P<milliseconds>
|
||||||
|
* G10 - retract filament according to settings of M207
|
||||||
* G2 - CW ARC
|
* G11 - retract recover filament according to settings of M208
|
||||||
* G3 - CCW ARC
|
* G28 - Home all Axis
|
||||||
|
* G90 - Use Absolute Coordinates
|
||||||
General:
|
* G91 - Use Relative Coordinates
|
||||||
|
* G92 - Set current position to cordinates given
|
||||||
* M17 - Enable/Power all stepper motors. Compatibility to ReplicatorG.
|
|
||||||
* M18 - Disable all stepper motors; same as M84.Compatibility to ReplicatorG.
|
M Codes
|
||||||
* M30 - Print time since last M109 or SD card start to serial
|
* M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled)
|
||||||
* M42 - Change pin status via gcode
|
* M1 - Same as M0
|
||||||
* M80 - Turn on Power Supply
|
* M17 - Enable/Power all stepper motors
|
||||||
* M81 - Turn off Power Supply
|
* M18 - Disable all stepper motors; same as M84
|
||||||
* M114 - Output current position to serial port
|
* M20 - List SD card
|
||||||
* M119 - Output Endstop status to serial port
|
* M21 - Init SD card
|
||||||
|
* M22 - Release SD card
|
||||||
Movement variables:
|
* M23 - Select SD file (M23 filename.g)
|
||||||
|
* M24 - Start/resume SD print
|
||||||
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
* M25 - Pause SD print
|
||||||
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
|
* M26 - Set SD position in bytes (M26 S12345)
|
||||||
* M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
|
* M27 - Report SD print status
|
||||||
* M206 - set home offsets. This sets the X,Y,Z coordinates of the endstops (and is added to the {X,Y,Z}_HOME_POS configuration options (and is also added to the coordinates, if any, provided to G82, as with earlier firmware)
|
* M28 - Start SD write (M28 filename.g)
|
||||||
* M220 - set build speed mulitplying S:factor in percent ; aka "realtime tuneing in the gcode". So you can slow down if you have islands in one height-range, and speed up otherwise.
|
* M29 - Stop SD write
|
||||||
* M221 - set the extrude multiplying S:factor in percent
|
* M30 - Delete file from SD (M30 filename.g)
|
||||||
* M400 - Finish all buffered moves.
|
* M31 - Output time since last M109 or SD card start to serial
|
||||||
|
* M32 - Select file and start SD print (Can be used when printing from SD card)
|
||||||
Temperature variables:
|
* M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
|
||||||
* M301 - Set PID parameters P I and D
|
* M80 - Turn on Power Supply
|
||||||
* M302 - Allow cold extrudes
|
* M81 - Turn off Power Supply
|
||||||
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
* M82 - Set E codes absolute (default)
|
||||||
|
* M83 - Set E codes relative while in Absolute Coordinates (G90) mode
|
||||||
Advance:
|
* M84 - Disable steppers until next move, or use S<seconds> to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout.
|
||||||
|
* M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
||||||
* M200 - Set filament diameter for advance
|
* M92 - Set axis_steps_per_unit - same syntax as G92
|
||||||
* M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
|
* M104 - Set extruder target temp
|
||||||
|
* M105 - Read current temp
|
||||||
EEPROM:
|
* M106 - Fan on
|
||||||
|
* M107 - Fan off
|
||||||
* M500 - stores paramters in EEPROM. This parameters are stored: axis_steps_per_unit, max_feedrate, max_acceleration ,acceleration,retract_acceleration,
|
* M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
|
||||||
minimumfeedrate,mintravelfeedrate,minsegmenttime, jerk velocities, PID
|
* Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
|
||||||
* M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
* M114 - Output current position to serial port
|
||||||
* M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
* M115 - Capabilities string
|
||||||
* M503 - print the current settings (from memory not from eeprom)
|
* M117 - display message
|
||||||
|
* M119 - Output Endstop status to serial port
|
||||||
MISC:
|
* M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
|
||||||
|
* M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
|
||||||
* M240 - Trigger a camera to take a photograph
|
* M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
||||||
* M999 - Restart after being stopped by error
|
* M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
|
||||||
|
* M140 - Set bed target temp
|
||||||
Configuring and compilation:
|
* M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
|
||||||
============================
|
* Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
|
||||||
|
* M200 - Set filament diameter
|
||||||
Install the arduino software IDE/toolset v23 (Some configurations also work with 1.x.x)
|
* M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
||||||
http://www.arduino.cc/en/Main/Software
|
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
|
||||||
|
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
|
||||||
For gen6/gen7 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
* M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
|
||||||
copy ArduinoAddons\Arduino_x.x.x\sanguino <arduino home>\hardware\Sanguino
|
* M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk
|
||||||
|
* M206 - set additional homeing offset
|
||||||
Install Ultimaker's RepG 25 build
|
* M207 - set retract length S[positive mm] F[feedrate mm/sec] Z[additional zlift/hop]
|
||||||
http://software.ultimaker.com
|
* M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec]
|
||||||
For SD handling and as better substitute (apart from stl manipulation) download
|
* M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
|
||||||
the very nice Kliment's printrun/pronterface https://github.com/kliment/Printrun
|
* M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
|
||||||
|
* M220 S<factor in percent>- set speed factor override percentage
|
||||||
Copy the Ultimaker Marlin firmware
|
* M221 S<factor in percent>- set extrude factor override percentage
|
||||||
https://github.com/ErikZalm/Marlin/tree/Marlin_v1
|
* M240 - Trigger a camera to take a photograph
|
||||||
(Use the download button)
|
* M280 - Position an RC Servo P<index> S<angle/microseconds>, ommit S to report back current angle
|
||||||
|
* M300 - Play beepsound S<frequency Hz> P<duration ms>
|
||||||
Start the arduino IDE.
|
* M301 - Set PID parameters P I and D
|
||||||
Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
* M302 - Allow cold extrudes
|
||||||
Select the correct serial port in Tools ->Serial Port
|
* M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C)
|
||||||
Open Marlin.pde
|
* M304 - Set bed PID parameters P I and D
|
||||||
|
* M400 - Finish all moves
|
||||||
Click the Verify/Compile button
|
* M500 - stores paramters in EEPROM
|
||||||
|
* M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
|
||||||
Click the Upload button
|
* M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
|
||||||
If all goes well the firmware is uploading
|
* M503 - print the current settings (from memory not from eeprom)
|
||||||
|
* M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
|
||||||
Start Ultimaker's Custom RepG 25
|
* M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
|
||||||
Make sure Show Experimental Profiles is enabled in Preferences
|
* M907 - Set digital trimpot motor current using axis codes.
|
||||||
Select Sprinter as the Driver
|
* M908 - Control digital trimpot directly.
|
||||||
|
* M350 - Set microstepping mode.
|
||||||
Press the Connect button.
|
* M351 - Toggle MS1 MS2 pins directly.
|
||||||
|
* M928 - Start SD logging (M928 filename.g) - ended by M29
|
||||||
KNOWN ISSUES: RepG will display: Unknown: marlin x.y.z
|
* M999 - Restart after being stopped by error
|
||||||
|
|
||||||
That's ok. Enjoy Silky Smooth Printing.
|
|
||||||
|
Configuring and compilation:
|
||||||
|
============================
|
||||||
|
|
||||||
|
Install the arduino software IDE/toolset v23 (Some configurations also work with 1.x.x)
|
||||||
|
http://www.arduino.cc/en/Main/Software
|
||||||
|
|
||||||
|
For gen6/gen7 and sanguinololu the Sanguino directory in the Marlin dir needs to be copied to the arduino environment.
|
||||||
|
copy ArduinoAddons\Arduino_x.x.x\sanguino <arduino home>\hardware\Sanguino
|
||||||
|
|
||||||
|
Copy the Marlin firmware
|
||||||
|
https://github.com/ErikZalm/Marlin/tree/Marlin_v1
|
||||||
|
(Use the download button)
|
||||||
|
|
||||||
|
Start the arduino IDE.
|
||||||
|
Select Tools -> Board -> Arduino Mega 2560 or your microcontroller
|
||||||
|
Select the correct serial port in Tools ->Serial Port
|
||||||
|
Open Marlin.pde
|
||||||
|
|
||||||
|
Click the Verify/Compile button
|
||||||
|
|
||||||
|
Click the Upload button
|
||||||
|
If all goes well the firmware is uploading
|
||||||
|
|
||||||
|
That's ok. Enjoy Silky Smooth Printing.
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
Reference in a new issue