Merge pull request #1 from ErikZalm/Marlin_v1

Update on 140315
This commit is contained in:
Dim3nsioneer 2014-03-15 17:49:30 +01:00
commit 8613a74443
31 changed files with 1039 additions and 661 deletions

View File

@ -8,7 +8,7 @@
//=========================================================================== //===========================================================================
//============================= DELTA Printer =============================== //============================= DELTA Printer ===============================
//=========================================================================== //===========================================================================
// For a Delta printer rplace the configuration files wilth the files in the // For a Delta printer replace the configuration files with the files in the
// example_configurations/delta directory. // example_configurations/delta directory.
// //
@ -55,6 +55,7 @@
// 68 = Azteeg X3 Pro // 68 = Azteeg X3 Pro
// 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)
// 72 = Ultimainboard 2.x (Uses TEMP_SENSOR 20)
// 77 = 3Drag Controller // 77 = 3Drag Controller
// 8 = Teensylu // 8 = Teensylu
// 80 = Rumba // 80 = Rumba
@ -105,7 +106,7 @@
// 0 is not used // 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup) // 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup) // 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is mendel-parts thermistor (4.7k pullup) // 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !! // 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup) // 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup) // 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
@ -114,13 +115,19 @@
// 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 // 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor
// //
// 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)
// 51 is 100k thermistor - EPCOS (1k pullup) // 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup) // 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup) // 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 -1 #define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1 #define TEMP_SENSOR_1 -1
@ -175,13 +182,13 @@
#define K1 0.95 //smoothing factor within the PID #define K1 0.95 //smoothing factor within the PID
#define PID_dT ((OVERSAMPLENR * 8.0)/(F_CPU / 64.0 / 256.0)) //sampling period of the temperature routine #define PID_dT ((OVERSAMPLENR * 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 pre-configured hotend then you can use one of the value sets by uncommenting it
// Ultimaker // Ultimaker
#define DEFAULT_Kp 22.2 #define DEFAULT_Kp 22.2
#define DEFAULT_Ki 1.08 #define DEFAULT_Ki 1.08
#define DEFAULT_Kd 114 #define DEFAULT_Kd 114
// Makergear // MakerGear
// #define DEFAULT_Kp 7.0 // #define DEFAULT_Kp 7.0
// #define DEFAULT_Ki 0.1 // #define DEFAULT_Ki 0.1
// #define DEFAULT_Kd 12 // #define DEFAULT_Kd 12
@ -250,7 +257,7 @@
#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 ignored if ENDSTOPPULLUPS is defined // fine endstop 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
@ -328,13 +335,51 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
// these are the positions on the bed to do the probing // There are 2 different ways to pick the X and Y locations to probe:
// - "grid" mode
// Probe every point in a rectangular grid
// You must specify the rectangle, and the density of sample points
// This mode is preferred because there are more measurements.
// It used to be called ACCURATE_BED_LEVELING but "grid" is more descriptive
// - "3-point" mode
// Probe 3 arbitrary points on the bed (that aren't colinear)
// You must specify the X & Y coordinates of all 3 points
#define AUTO_BED_LEVELING_GRID
// with AUTO_BED_LEVELING_GRID, the bed is sampled in a
// AUTO_BED_LEVELING_GRID_POINTSxAUTO_BED_LEVELING_GRID_POINTS grid
// and least squares solution is calculated
// Note: this feature occupies 10'206 byte
#ifdef AUTO_BED_LEVELING_GRID
// set the rectangle in which to probe
#define LEFT_PROBE_BED_POSITION 15 #define LEFT_PROBE_BED_POSITION 15
#define RIGHT_PROBE_BED_POSITION 170 #define RIGHT_PROBE_BED_POSITION 170
#define BACK_PROBE_BED_POSITION 180 #define BACK_PROBE_BED_POSITION 180
#define FRONT_PROBE_BED_POSITION 20 #define FRONT_PROBE_BED_POSITION 20
// these are the offsets to the prob relative to the extruder tip (Hotend - Probe) // set the number of grid points per dimension
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
#define AUTO_BED_LEVELING_GRID_POINTS 2
#else // not AUTO_BED_LEVELING_GRID
// with no grid, just probe 3 arbitrary points. A simple cross-product
// is used to esimate the plane of the print bed
#define ABL_PROBE_PT_1_X 15
#define ABL_PROBE_PT_1_Y 180
#define ABL_PROBE_PT_2_X 15
#define ABL_PROBE_PT_2_Y 20
#define ABL_PROBE_PT_3_X 170
#define ABL_PROBE_PT_3_Y 20
#endif // AUTO_BED_LEVELING_GRID
// these are the offsets to the probe relative to the extruder tip (Hotend - Probe)
#define X_PROBE_OFFSET_FROM_EXTRUDER -25 #define X_PROBE_OFFSET_FROM_EXTRUDER -25
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29 #define Y_PROBE_OFFSET_FROM_EXTRUDER -29
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35 #define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
@ -355,7 +400,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// #define PROBE_SERVO_DEACTIVATION_DELAY 300 // #define PROBE_SERVO_DEACTIVATION_DELAY 300
//If you have enabled the Bed Auto Levelling and are using the same Z Probe for Z Homing, //If you have enabled the Bed Auto Leveling and are using the same Z Probe for Z Homing,
//it is highly recommended you let this Z_SAFE_HOMING enabled!!! //it is highly recommended you let this Z_SAFE_HOMING enabled!!!
#define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area. #define Z_SAFE_HOMING // This feature is meant to avoid Z homing with probe outside the bed area.
@ -372,16 +417,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#endif #endif
// with accurate bed leveling, the bed is sampled in a ACCURATE_BED_LEVELING_POINTSxACCURATE_BED_LEVELING_POINTS grid and least squares solution is calculated #endif // ENABLE_AUTO_BED_LEVELING
// Note: this feature occupies 10'206 byte
#define ACCURATE_BED_LEVELING
#ifdef ACCURATE_BED_LEVELING
// I wouldn't see a reason to go above 3 (=9 probing points on the bed)
#define ACCURATE_BED_LEVELING_POINTS 2
#endif
#endif
// The position of the homing switches // The position of the homing switches
@ -389,7 +425,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#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. // 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
@ -403,7 +439,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#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 retracts #define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
@ -424,11 +460,11 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//=========================================================================== //===========================================================================
// EEPROM // EEPROM
// the microcontroller can store settings in the EEPROM, e.g. max velocity... // The microcontroller can store settings in the EEPROM, e.g. max velocity...
// M500 - stores paramters in EEPROM // M500 - stores parameters in EEPROM
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
//define this to enable eeprom support //define this to enable EEPROM support
//#define EEPROM_SETTINGS //#define EEPROM_SETTINGS
//to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out: //to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
// please keep turned on if you can. // please keep turned on if you can.
@ -444,14 +480,14 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255 #define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
//LCD and SD support //LCD and SD support
//#define ULTRA_LCD //general lcd support, also 16x2 //#define ULTRA_LCD //general LCD support, also 16x2
//#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family) //#define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family)
//#define SDSUPPORT // Enable SD Card Support in Hardware Console //#define SDSUPPORT // Enable SD Card Support in Hardware Console
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error) //#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
//#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder //#define ENCODER_PULSES_PER_STEP 1 // Increase if you have a high resolution encoder
//#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking //#define ENCODER_STEPS_PER_MENU_ITEM 5 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the ultimaker online store. //#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the ultipanel as on thingiverse //#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click //#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click
//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click //#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 // the duration the buzzer plays the UI feedback sound. ie Screen Click
@ -592,7 +628,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define LCD_WIDTH 20 #define LCD_WIDTH 20
#define LCD_HEIGHT 4 #define LCD_HEIGHT 4
#endif #endif
#else //no panel but just lcd #else //no panel but just LCD
#ifdef ULTRA_LCD #ifdef ULTRA_LCD
#ifdef DOGLCD // Change number of lines to match the 128x64 graphics display #ifdef DOGLCD // Change number of lines to match the 128x64 graphics display
#define LCD_WIDTH 20 #define LCD_WIDTH 20
@ -614,8 +650,8 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// 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
// Temperature status leds that display the hotend and bet temperature. // Temperature status LEDs that display the hotend and bet temperature.
// If alle hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on. // If all hotends and bed temperature and temperature setpoint are < 54C then the BLUE led is on.
// Otherwise the RED led is on. There is 1C hysteresis. // Otherwise the RED led is on. There is 1C hysteresis.
//#define TEMP_STAT_LEDS //#define TEMP_STAT_LEDS

View File

@ -37,7 +37,11 @@ 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.
#ifdef DELTA
#define EEPROM_VERSION "V11"
#else
#define EEPROM_VERSION "V10" #define EEPROM_VERSION "V10"
#endif
#ifdef EEPROM_SETTINGS #ifdef EEPROM_SETTINGS
void Config_StoreSettings() void Config_StoreSettings()
@ -59,6 +63,9 @@ void Config_StoreSettings()
EEPROM_WRITE_VAR(i,add_homeing); EEPROM_WRITE_VAR(i,add_homeing);
#ifdef DELTA #ifdef DELTA
EEPROM_WRITE_VAR(i,endstop_adj); EEPROM_WRITE_VAR(i,endstop_adj);
EEPROM_WRITE_VAR(i,delta_radius);
EEPROM_WRITE_VAR(i,delta_diagonal_rod);
EEPROM_WRITE_VAR(i,delta_segments_per_second);
#endif #endif
#ifndef ULTIPANEL #ifndef ULTIPANEL
int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED; int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED;
@ -157,6 +164,13 @@ void Config_PrintSettings()
SERIAL_ECHOPAIR(" Y" ,endstop_adj[1] ); SERIAL_ECHOPAIR(" Y" ,endstop_adj[1] );
SERIAL_ECHOPAIR(" Z" ,endstop_adj[2] ); SERIAL_ECHOPAIR(" Z" ,endstop_adj[2] );
SERIAL_ECHOLN(""); SERIAL_ECHOLN("");
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM("Delta settings: L=delta_diagonal_rod, R=delta_radius, S=delta_segments_per_second");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M665 L",delta_diagonal_rod );
SERIAL_ECHOPAIR(" R" ,delta_radius );
SERIAL_ECHOPAIR(" S" ,delta_segments_per_second );
SERIAL_ECHOLN("");
#endif #endif
#ifdef PIDTEMP #ifdef PIDTEMP
SERIAL_ECHO_START; SERIAL_ECHO_START;
@ -200,6 +214,9 @@ void Config_RetrieveSettings()
EEPROM_READ_VAR(i,add_homeing); EEPROM_READ_VAR(i,add_homeing);
#ifdef DELTA #ifdef DELTA
EEPROM_READ_VAR(i,endstop_adj); EEPROM_READ_VAR(i,endstop_adj);
EEPROM_READ_VAR(i,delta_radius);
EEPROM_READ_VAR(i,delta_diagonal_rod);
EEPROM_READ_VAR(i,delta_segments_per_second);
#endif #endif
#ifndef ULTIPANEL #ifndef ULTIPANEL
int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed; int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed;
@ -265,6 +282,10 @@ void Config_ResetDefault()
add_homeing[0] = add_homeing[1] = add_homeing[2] = 0; add_homeing[0] = add_homeing[1] = add_homeing[2] = 0;
#ifdef DELTA #ifdef DELTA
endstop_adj[0] = endstop_adj[1] = endstop_adj[2] = 0; endstop_adj[0] = endstop_adj[1] = endstop_adj[2] = 0;
delta_radius= DELTA_RADIUS;
delta_diagonal_rod= DELTA_DIAGONAL_ROD;
delta_segments_per_second= DELTA_SEGMENTS_PER_SECOND;
recalc_delta_settings(delta_radius, delta_diagonal_rod);
#endif #endif
#ifdef ULTIPANEL #ifdef ULTIPANEL
plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP; plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP;

View File

@ -20,7 +20,7 @@
#ifdef PIDTEMP #ifdef PIDTEMP
// this adds an experimental additional term to the heating power, proportional to the extrusion speed. // this adds an experimental additional term to the heating power, proportional to the extrusion speed.
// if Kc is choosen well, the additional required power due to increased melting should be compensated. // if Kc is chosen well, the additional required power due to increased melting should be compensated.
#define PID_ADD_EXTRUSION_RATE #define PID_ADD_EXTRUSION_RATE
#ifdef PID_ADD_EXTRUSION_RATE #ifdef PID_ADD_EXTRUSION_RATE
#define DEFAULT_Kc (1) //heating power=Kc*(e_speed) #define DEFAULT_Kc (1) //heating power=Kc*(e_speed)
@ -34,7 +34,7 @@
// the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp // the target temperature is set to mintemp+factor*se[steps/sec] and limited by mintemp and maxtemp
// you exit the value by any M109 without F* // you exit the value by any M109 without F*
// Also, if the temperature is set to a value <mintemp, it is not changed by autotemp. // Also, if the temperature is set to a value <mintemp, it is not changed by autotemp.
// on an ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode // on an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode
#define AUTOTEMP #define AUTOTEMP
#ifdef AUTOTEMP #ifdef AUTOTEMP
#define AUTOTEMP_OLDWEIGHT 0.98 #define AUTOTEMP_OLDWEIGHT 0.98
@ -239,6 +239,11 @@
#define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // set the speeds for manual moves (mm/min) #define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // set the speeds for manual moves (mm/min)
#endif #endif
//Comment to disable setting feedrate multiplier via encoder
#ifdef ULTIPANEL
#define ULTIPANEL_FEEDMULTIPLY
#endif
// minimum time in microseconds that a movement needs to take if the buffer is emptied. // minimum time in microseconds that a movement needs to take if the buffer is emptied.
#define DEFAULT_MINSEGMENTTIME 20000 #define DEFAULT_MINSEGMENTTIME 20000
@ -279,15 +284,18 @@
//=============================Additional Features=========================== //=============================Additional Features===========================
//=========================================================================== //===========================================================================
//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/
#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers? #define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place. #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
#define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order. #define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order.
// if a file is deleted, it frees a block. hence, the order is not purely cronological. To still have auto0.g accessible, there is again the option to do that. // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that.
// using: // using:
//#define MENU_ADDAUTOSTART //#define MENU_ADDAUTOSTART
// The hardware watchdog should reset the Microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation. // The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
//#define USE_WATCHDOG //#define USE_WATCHDOG
#ifdef USE_WATCHDOG #ifdef USE_WATCHDOG
@ -301,7 +309,7 @@
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED
// Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process // Babystepping enables the user to control the axis in tiny amounts, independently from the normal printing process
// it can e.g. be used to change z-positions in the print startup phase in realtime // it can e.g. be used to change z-positions in the print startup phase in real-time
// does not respect endstops! // does not respect endstops!
//#define BABYSTEPPING //#define BABYSTEPPING
#ifdef BABYSTEPPING #ifdef BABYSTEPPING
@ -324,8 +332,8 @@
// //
// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTUDER_ADVANCE_K * cubic mm per second ^ 2 // advance (steps) = STEPS_PER_CUBIC_MM_E * EXTUDER_ADVANCE_K * cubic mm per second ^ 2
// //
// hooke's law says: force = k * distance // Hooke's law says: force = k * distance
// bernoulli's priniciple says: v ^ 2 / 2 + g . h + pressure / density = constant // Bernoulli's principle says: v ^ 2 / 2 + g . h + pressure / density = constant
// so: v ^ 2 is proportional to number of steps we advance the extruder // so: v ^ 2 is proportional to number of steps we advance the extruder
//#define ADVANCE //#define ADVANCE
@ -379,7 +387,7 @@ const unsigned int dropsegments=5; //everything with less than this number of st
//=========================================================================== //===========================================================================
// The number of linear motions that can be in the plan at any give time. // The number of linear motions that can be in the plan at any give time.
// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ringbuffering. // THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering.
#if defined SDSUPPORT #if defined SDSUPPORT
#define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller
#else #else
@ -387,20 +395,26 @@ const unsigned int dropsegments=5; //everything with less than this number of st
#endif #endif
//The ASCII buffer for recieving from the serial: //The ASCII buffer for receiving from the serial:
#define MAX_CMD_SIZE 96 #define MAX_CMD_SIZE 96
#define BUFSIZE 4 #define BUFSIZE 4
// Firmware based and LCD controled retract // Firmware based and LCD controlled retract
// M207 and M208 can be used to define parameters for the retraction. // M207 and M208 can be used to define parameters for the retraction.
// The retraction can be called by the slicer using G10 and G11 // The retraction can be called by the slicer using G10 and G11
// until then, intended retractions can be detected by moves that only extrude and the direction. // until then, intended retractions can be detected by moves that only extrude and the direction.
// the moves are than replaced by the firmware controlled ones. // the moves are than replaced by the firmware controlled ones.
// #define FWRETRACT //ONLY PARTIALLY TESTED // #define FWRETRACT //ONLY PARTIALLY TESTED
#ifdef FWRETRACT
#define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt
#define RETRACT_LENGTH 3 //default retract length (positive mm)
#define RETRACT_FEEDRATE 80*60 //default feedrate for retracting
#define RETRACT_ZLIFT 0 //default retract Z-lift
#define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering)
#define RETRACT_RECOVER_FEEDRATE 8*60 //default feedrate for recovering from retraction
#endif
//adds support for experimental filament exchange support M600; requires display //adds support for experimental filament exchange support M600; requires display
#ifdef ULTIPANEL #ifdef ULTIPANEL

Binary file not shown.

View File

@ -11,7 +11,7 @@
#include "WProgram.h" #include "WProgram.h"
#endif #endif
// it is a russian alphabet translation // it is a Russian alphabet translation
// except 0401 --> 0xa2 = ╗, 0451 --> 0xb5 // except 0401 --> 0xa2 = ╗, 0451 --> 0xb5
const PROGMEM uint8_t utf_recode[] = const PROGMEM uint8_t utf_recode[] =
{ 0x41,0xa0,0x42,0xa1,0xe0,0x45,0xa3,0xa4,0xa5,0xa6,0x4b,0xa7,0x4d,0x48,0x4f, { 0x41,0xa0,0x42,0xa1,0xe0,0x45,0xa3,0xa4,0xa5,0xa6,0x4b,0xa7,0x4d,0x48,0x4f,
@ -115,7 +115,7 @@ void LiquidCrystalRus::begin(uint8_t cols, uint8_t lines, uint8_t dotsize) {
// SEE PAGE 45/46 FOR INITIALIZATION SPECIFICATION! // SEE PAGE 45/46 FOR INITIALIZATION SPECIFICATION!
// according to datasheet, we need at least 40ms after power rises above 2.7V // according to datasheet, we need at least 40ms after power rises above 2.7V
// before sending commands. Arduino can turn on way befer 4.5V so we'll wait 50 // before sending commands. Arduino can turn on way before 4.5V so we'll wait 50
delayMicroseconds(50000); delayMicroseconds(50000);
// Now we pull both RS and R/W low to begin commands // Now we pull both RS and R/W low to begin commands
digitalWrite(_rs_pin, LOW); digitalWrite(_rs_pin, LOW);
@ -126,7 +126,7 @@ void LiquidCrystalRus::begin(uint8_t cols, uint8_t lines, uint8_t dotsize) {
//put the LCD into 4 bit or 8 bit mode //put the LCD into 4 bit or 8 bit mode
if (! (_displayfunction & LCD_8BITMODE)) { if (! (_displayfunction & LCD_8BITMODE)) {
// this is according to the hitachi HD44780 datasheet // this is according to the Hitachi HD44780 datasheet
// figure 24, pg 46 // figure 24, pg 46
// we start in 8bit mode, try to set 4 bit mode // we start in 8bit mode, try to set 4 bit mode
@ -144,7 +144,7 @@ void LiquidCrystalRus::begin(uint8_t cols, uint8_t lines, uint8_t dotsize) {
// finally, set to 8-bit interface // finally, set to 8-bit interface
writeNbits(0x02,4); writeNbits(0x02,4);
} else { } else {
// this is according to the hitachi HD44780 datasheet // this is according to the Hitachi HD44780 datasheet
// page 45 figure 23 // page 45 figure 23
// Send function set command sequence // Send function set command sequence
@ -308,7 +308,7 @@ inline void LiquidCrystalRus::command(uint8_t value) {
} }
} else send(out_char, HIGH); } else send(out_char, HIGH);
#if defined(ARDUINO) && ARDUINO >= 100 #if defined(ARDUINO) && ARDUINO >= 100
return 1; // assume sucess return 1; // assume success
#endif #endif
} }

View File

@ -236,7 +236,7 @@ VPATH += $(HARDWARE_DIR)/libraries/Wire
VPATH += $(HARDWARE_DIR)/libraries/Wire/utility VPATH += $(HARDWARE_DIR)/libraries/Wire/utility
VPATH += $(HARDWARE_DIR)/libraries/LiquidTWI2 VPATH += $(HARDWARE_DIR)/libraries/LiquidTWI2
endif endif
ifeq ($(WIRE, 1) ifeq ($(WIRE), 1)
VPATH += $(HARDWARE_DIR)/libraries/Wire VPATH += $(HARDWARE_DIR)/libraries/Wire
VPATH += $(HARDWARE_DIR)/libraries/Wire/utility VPATH += $(HARDWARE_DIR)/libraries/Wire/utility
endif endif
@ -260,7 +260,8 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \
MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \ MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.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 SPI.cpp Servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp watchdog.cpp SPI.cpp Servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \
vector_3.cpp qr_solve.cpp
ifeq ($(LIQUID_TWI2), 0) ifeq ($(LIQUID_TWI2), 0)
CXXSRC += LiquidCrystal.cpp CXXSRC += LiquidCrystal.cpp
else else

View File

@ -1,5 +1,5 @@
// Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware. // Tonokip RepRap firmware rewrite based off of Hydra-mmm firmware.
// Licence: GPL // License: GPL
#ifndef MARLIN_H #ifndef MARLIN_H
#define MARLIN_H #define MARLIN_H
@ -30,7 +30,7 @@
# include "Arduino.h" # include "Arduino.h"
#else #else
# include "WProgram.h" # include "WProgram.h"
//Arduino < 1.0.0 does not define this, so we need to do it ourselfs //Arduino < 1.0.0 does not define this, so we need to do it ourselves
# define analogInputToDigitalPin(p) ((p) + A0) # define analogInputToDigitalPin(p) ((p) + A0)
#endif #endif
@ -87,7 +87,7 @@ void serial_echopair_P(const char *s_P, double v);
void serial_echopair_P(const char *s_P, unsigned long v); void serial_echopair_P(const char *s_P, unsigned long v);
//things to write to serial from Programmemory. saves 400 to 2k of RAM. //Things to write to serial from Program memory. Saves 400 to 2k of RAM.
FORCE_INLINE void serialprintPGM(const char *str) FORCE_INLINE void serialprintPGM(const char *str)
{ {
char ch=pgm_read_byte(str); char ch=pgm_read_byte(str);
@ -184,11 +184,13 @@ void Stop();
bool IsStopped(); bool IsStopped();
void enquecommand(const char *cmd); //put an ascii command at the end of the current buffer. void enquecommand(const char *cmd); //put an ASCII command at the end of the current buffer.
void enquecommand_P(const char *cmd); //put an ascii command at the end of the current buffer, read from flash void enquecommand_P(const char *cmd); //put an ASCII command at the end of the current buffer, read from flash
void prepare_arc_move(char isclockwise); void prepare_arc_move(char isclockwise);
void clamp_to_software_endstops(float target[3]); void clamp_to_software_endstops(float target[3]);
void refresh_cmd_timeout(void);
#ifdef FAST_PWM_FAN #ifdef FAST_PWM_FAN
void setPwmFrequency(uint8_t pin, int val); void setPwmFrequency(uint8_t pin, int val);
#endif #endif
@ -207,6 +209,10 @@ extern float current_position[NUM_AXIS] ;
extern float add_homeing[3]; extern float add_homeing[3];
#ifdef DELTA #ifdef DELTA
extern float endstop_adj[3]; extern float endstop_adj[3];
extern float delta_radius;
extern float delta_diagonal_rod;
extern float delta_segments_per_second;
void recalc_delta_settings(float radius, float diagonal_rod);
#endif #endif
extern float min_pos[3]; extern float min_pos[3];
extern float max_pos[3]; extern float max_pos[3];

View File

@ -25,7 +25,7 @@
#ifndef AT90USB #ifndef AT90USB
// this next line disables the entire HardwareSerial.cpp, // this next line disables the entire HardwareSerial.cpp,
// this is so I can support Attiny series and any other chip without a uart // this is so I can support Attiny series and any other chip without a UART
#if defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H) #if defined(UBRRH) || defined(UBRR0H) || defined(UBRR1H) || defined(UBRR2H) || defined(UBRR3H)
#if UART_PRESENT(SERIAL_PORT) #if UART_PRESENT(SERIAL_PORT)

View File

@ -31,7 +31,7 @@
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
#include "vector_3.h" #include "vector_3.h"
#ifdef ACCURATE_BED_LEVELING #ifdef AUTO_BED_LEVELING_GRID
#include "qr_solve.h" #include "qr_solve.h"
#endif #endif
#endif // ENABLE_AUTO_BED_LEVELING #endif // ENABLE_AUTO_BED_LEVELING
@ -63,7 +63,7 @@
#define VERSION_STRING "1.0.0" #define VERSION_STRING "1.0.0"
// look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html // look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html
// http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
//Implemented Codes //Implemented Codes
@ -76,11 +76,11 @@
// G10 - retract filament according to settings of M207 // G10 - retract filament according to settings of M207
// G11 - retract recover filament according to settings of M208 // G11 - retract recover filament according to settings of M208
// G28 - Home all Axis // G28 - Home all Axis
// G29 - Detailed Z-Probe, probes the bed at 3 points. You must de at the home position for this to work correctly. // G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet.
// G30 - Single Z Probe, probes bed at current XY location. // G30 - Single Z Probe, probes bed at current XY location.
// G90 - Use Absolute Coordinates // G90 - Use Absolute Coordinates
// G91 - Use Relative Coordinates // G91 - Use Relative Coordinates
// G92 - Set current position to cordinates given // G92 - Set current position to coordinates given
// 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)
@ -101,7 +101,7 @@
// 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 _while_ printing from SD card files): // M32 - Select file and start SD print (Can be used _while_ printing from SD card files):
// syntax "M32 /path/filename#", or "M32 S<startpos bytes> !filename#" // syntax "M32 /path/filename#", or "M32 S<startpos bytes> !filename#"
// Call gcode file : "M32 P !filename#" and return to caller file after finishing (simiarl to #include). // Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include).
// The '#' is necessary when calling from within sd files, as it stops buffer prereading // The '#' is necessary when calling from within sd files, as it stops buffer prereading
// 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
@ -127,17 +127,17 @@
// 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
// M150 - Set BlinkM Colour Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work. // M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work.
// M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating // 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 // Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
// M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters). // M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
// 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!!
// M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec // M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec
// 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 // M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate
// 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 // 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 // M206 - set additional homing offset
// M207 - set retract length S[positive mm] F[feedrate mm/sec] Z[additional zlift/hop] // M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting
// M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec] // M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec]
// 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. // 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.
// M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y> // M218 - set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
@ -155,13 +155,14 @@
// M400 - Finish all moves // M400 - Finish all moves
// M401 - Lower z-probe if present // M401 - Lower z-probe if present
// M402 - Raise z-probe if present // M402 - Raise z-probe if present
// M500 - stores paramters in EEPROM // M500 - stores parameters in EEPROM
// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).
// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to.
// M503 - print the current settings (from memory not from eeprom) // 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) // M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
// M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal] // M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
// M666 - set delta endstop adjustemnt // M665 - set delta configurations
// M666 - set delta endstop adjustment
// M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ] // M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
// M907 - Set digital trimpot motor current using axis codes. // M907 - Set digital trimpot motor current using axis codes.
// M908 - Control digital trimpot directly. // M908 - Control digital trimpot directly.
@ -231,10 +232,13 @@ int EtoPPressure=0;
#endif #endif
#ifdef FWRETRACT #ifdef FWRETRACT
bool autoretract_enabled=true; bool autoretract_enabled=false;
bool retracted=false; bool retracted=false;
float retract_length=3, retract_feedrate=17*60, retract_zlift=0.8; float retract_length = RETRACT_LENGTH;
float retract_recover_length=0, retract_recover_feedrate=8*60; float retract_feedrate = RETRACT_FEEDRATE;
float retract_zlift = RETRACT_ZLIFT;
float retract_recover_length = RETRACT_RECOVER_LENGTH;
float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE;
#endif #endif
#ifdef ULTIPANEL #ifdef ULTIPANEL
@ -247,11 +251,23 @@ int EtoPPressure=0;
#ifdef DELTA #ifdef DELTA
float delta[3] = {0.0, 0.0, 0.0}; float delta[3] = {0.0, 0.0, 0.0};
#define SIN_60 0.8660254037844386
#define COS_60 0.5
// these are the default values, can be overriden with M665
float delta_radius= DELTA_RADIUS;
float delta_tower1_x= -SIN_60*delta_radius; // front left tower
float delta_tower1_y= -COS_60*delta_radius;
float delta_tower2_x= SIN_60*delta_radius; // front right tower
float delta_tower2_y= -COS_60*delta_radius;
float delta_tower3_x= 0.0; // back middle tower
float delta_tower3_y= delta_radius;
float delta_diagonal_rod= DELTA_DIAGONAL_ROD;
float delta_diagonal_rod_2= sq(delta_diagonal_rod);
float delta_segments_per_second= DELTA_SEGMENTS_PER_SECOND;
#endif #endif
//=========================================================================== //===========================================================================
//=============================private variables============================= //=============================Private Variables=============================
//=========================================================================== //===========================================================================
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};
@ -271,7 +287,7 @@ static int buflen = 0;
static char serial_char; static char serial_char;
static int serial_count = 0; static int serial_count = 0;
static boolean comment_mode = false; static boolean comment_mode = false;
static char *strchr_pointer; // just a pointer to find chars in the cmd string like X, Y, Z, E, etc static char *strchr_pointer; // just a pointer to find chars in the command string like X, Y, Z, E, etc
const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42 const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
@ -298,8 +314,14 @@ bool Stopped=false;
bool CooldownNoWait = true; bool CooldownNoWait = true;
bool target_direction; bool target_direction;
//Insert variables if CHDK is defined
#ifdef CHDK
unsigned long chdkHigh = 0;
boolean chdkActive = false;
#endif
//=========================================================================== //===========================================================================
//=============================ROUTINES============================= //=============================Routines======================================
//=========================================================================== //===========================================================================
void get_arc_coordinates(); void get_arc_coordinates();
@ -336,7 +358,7 @@ void enquecommand(const char *cmd)
{ {
if(buflen < BUFSIZE) if(buflen < BUFSIZE)
{ {
//this is dangerous if a mixing of serial and this happsens //this is dangerous if a mixing of serial and this happens
strcpy(&(cmdbuffer[bufindw][0]),cmd); strcpy(&(cmdbuffer[bufindw][0]),cmd);
SERIAL_ECHO_START; SERIAL_ECHO_START;
SERIAL_ECHOPGM("enqueing \""); SERIAL_ECHOPGM("enqueing \"");
@ -351,7 +373,7 @@ void enquecommand_P(const char *cmd)
{ {
if(buflen < BUFSIZE) if(buflen < BUFSIZE)
{ {
//this is dangerous if a mixing of serial and this happsens //this is dangerous if a mixing of serial and this happens
strcpy_P(&(cmdbuffer[bufindw][0]),cmd); strcpy_P(&(cmdbuffer[bufindw][0]),cmd);
SERIAL_ECHO_START; SERIAL_ECHO_START;
SERIAL_ECHOPGM("enqueing \""); SERIAL_ECHOPGM("enqueing \"");
@ -658,9 +680,9 @@ void get_command()
return; return;
} }
//'#' stops reading from sd to the buffer prematurely, so procedural macro calls are possible //'#' stops reading from SD to the buffer prematurely, so procedural macro calls are possible
// if it occures, stop_buffering is triggered and the buffer is ran dry. // if it occurs, stop_buffering is triggered and the buffer is ran dry.
// this character _can_ occure in serial com, due to checksums. however, no checksums are used in sd printing // this character _can_ occur in serial com, due to checksums. however, no checksums are used in SD printing
static bool stop_buffering=false; static bool stop_buffering=false;
if(buflen==0) stop_buffering=false; if(buflen==0) stop_buffering=false;
@ -819,7 +841,7 @@ static void axis_is_at_home(int axis) {
} }
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
#ifdef ACCURATE_BED_LEVELING #ifdef AUTO_BED_LEVELING_GRID
static void set_bed_level_equation_lsq(double *plane_equation_coefficients) static void set_bed_level_equation_lsq(double *plane_equation_coefficients)
{ {
vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1); vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1);
@ -843,42 +865,36 @@ static void set_bed_level_equation_lsq(double *plane_equation_coefficients)
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]);
} }
#else #else // not AUTO_BED_LEVELING_GRID
static void set_bed_level_equation(float z_at_xLeft_yFront, float z_at_xRight_yFront, float z_at_xLeft_yBack) {
static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float z_at_pt_3) {
plan_bed_level_matrix.set_to_identity(); plan_bed_level_matrix.set_to_identity();
vector_3 xLeftyFront = vector_3(LEFT_PROBE_BED_POSITION, FRONT_PROBE_BED_POSITION, z_at_xLeft_yFront); vector_3 pt1 = vector_3(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, z_at_pt_1);
vector_3 xLeftyBack = vector_3(LEFT_PROBE_BED_POSITION, BACK_PROBE_BED_POSITION, z_at_xLeft_yBack); vector_3 pt2 = vector_3(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, z_at_pt_2);
vector_3 xRightyFront = vector_3(RIGHT_PROBE_BED_POSITION, FRONT_PROBE_BED_POSITION, z_at_xRight_yFront); vector_3 pt3 = vector_3(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, z_at_pt_3);
vector_3 xPositive = (xRightyFront - xLeftyFront).get_normal(); vector_3 from_2_to_1 = (pt1 - pt2).get_normal();
vector_3 yPositive = (xLeftyBack - xLeftyFront).get_normal(); vector_3 from_2_to_3 = (pt3 - pt2).get_normal();
vector_3 planeNormal = vector_3::cross(xPositive, yPositive).get_normal(); vector_3 planeNormal = vector_3::cross(from_2_to_1, from_2_to_3).get_normal();
planeNormal = vector_3(planeNormal.x, planeNormal.y, abs(planeNormal.z));
//planeNormal.debug("planeNormal");
//yPositive.debug("yPositive");
plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal); plan_bed_level_matrix = matrix_3x3::create_look_at(planeNormal);
//bedLevel.debug("bedLevel");
//plan_bed_level_matrix.debug("bed level before");
//vector_3 uncorrected_position = plan_get_position_mm();
//uncorrected_position.debug("position before");
// and set our bed level equation to do the right thing
//plan_bed_level_matrix.debug("bed level after");
vector_3 corrected_position = plan_get_position(); vector_3 corrected_position = plan_get_position();
//corrected_position.debug("position after");
current_position[X_AXIS] = corrected_position.x; current_position[X_AXIS] = corrected_position.x;
current_position[Y_AXIS] = corrected_position.y; current_position[Y_AXIS] = corrected_position.y;
current_position[Z_AXIS] = corrected_position.z; current_position[Z_AXIS] = corrected_position.z;
// but the bed at 0 so we don't go below it. // put the bed at 0 so we don't go below it.
current_position[Z_AXIS] = zprobe_zoffset; current_position[Z_AXIS] = zprobe_zoffset;
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 // ACCURATE_BED_LEVELING
#endif // AUTO_BED_LEVELING_GRID
static void run_z_probe() { static void run_z_probe() {
plan_bed_level_matrix.set_to_identity(); plan_bed_level_matrix.set_to_identity();
@ -978,6 +994,28 @@ static void retract_z_probe() {
#endif #endif
} }
/// Probe bed height at position (x,y), returns the measured z value
static float probe_pt(float x, float y, float z_before) {
// move to right place
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z_before);
do_blocking_move_to(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
engage_z_probe(); // Engage Z Servo endstop if available
run_z_probe();
float measured_z = current_position[Z_AXIS];
retract_z_probe();
SERIAL_PROTOCOLPGM(MSG_BED);
SERIAL_PROTOCOLPGM(" x: ");
SERIAL_PROTOCOL(x);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL(y);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL(measured_z);
SERIAL_PROTOCOLPGM("\n");
return measured_z;
}
#endif // #ifdef ENABLE_AUTO_BED_LEVELING #endif // #ifdef ENABLE_AUTO_BED_LEVELING
static void homeaxis(int axis) { static void homeaxis(int axis) {
@ -1058,6 +1096,46 @@ static void homeaxis(int axis) {
} }
} }
#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS) #define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
void refresh_cmd_timeout(void)
{
previous_millis_cmd = millis();
}
#ifdef FWRETRACT
void retract(bool retracting) {
if(retracting && !retracted) {
destination[X_AXIS]=current_position[X_AXIS];
destination[Y_AXIS]=current_position[Y_AXIS];
destination[Z_AXIS]=current_position[Z_AXIS];
destination[E_AXIS]=current_position[E_AXIS];
current_position[E_AXIS]+=retract_length/volumetric_multiplier[active_extruder];
plan_set_e_position(current_position[E_AXIS]);
float oldFeedrate = feedrate;
feedrate=retract_feedrate;
retracted=true;
prepare_move();
current_position[Z_AXIS]-=retract_zlift;
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
prepare_move();
feedrate = oldFeedrate;
} else if(!retracting && retracted) {
destination[X_AXIS]=current_position[X_AXIS];
destination[Y_AXIS]=current_position[Y_AXIS];
destination[Z_AXIS]=current_position[Z_AXIS];
destination[E_AXIS]=current_position[E_AXIS];
current_position[Z_AXIS]+=retract_zlift;
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
//prepare_move();
current_position[E_AXIS]-=(retract_length+retract_recover_length)/volumetric_multiplier[active_extruder];
plan_set_e_position(current_position[E_AXIS]);
float oldFeedrate = feedrate;
feedrate=retract_recover_feedrate;
retracted=false;
prepare_move();
feedrate = oldFeedrate;
}
} //retract
#endif //FWRETRACT
void process_commands() void process_commands()
{ {
@ -1074,6 +1152,18 @@ void process_commands()
case 1: // G1 case 1: // G1
if(Stopped == false) { if(Stopped == false) {
get_coordinates(); // For X Y Z E F get_coordinates(); // For X Y Z E F
#ifdef FWRETRACT
if(autoretract_enabled)
if( !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
float echange=destination[E_AXIS]-current_position[E_AXIS];
if((echange<-MIN_RETRACT && !retracted) || (echange>MIN_RETRACT && retracted)) { //move appears to be an attempt to retract or recover
current_position[E_AXIS] = destination[E_AXIS]; //hide the slicer-generated retract/recover from calculations
plan_set_e_position(current_position[E_AXIS]); //AND from the planner
retract(!retracted);
return;
}
}
#endif //FWRETRACT
prepare_move(); prepare_move();
//ClearToSend(); //ClearToSend();
return; return;
@ -1108,31 +1198,10 @@ void process_commands()
break; break;
#ifdef FWRETRACT #ifdef FWRETRACT
case 10: // G10 retract case 10: // G10 retract
if(!retracted) retract(true);
{
destination[X_AXIS]=current_position[X_AXIS];
destination[Y_AXIS]=current_position[Y_AXIS];
destination[Z_AXIS]=current_position[Z_AXIS];
current_position[Z_AXIS]+=-retract_zlift;
destination[E_AXIS]=current_position[E_AXIS]-retract_length;
feedrate=retract_feedrate;
retracted=true;
prepare_move();
}
break; break;
case 11: // G11 retract_recover case 11: // G11 retract_recover
if(retracted) retract(false);
{
destination[X_AXIS]=current_position[X_AXIS];
destination[Y_AXIS]=current_position[Y_AXIS];
destination[Z_AXIS]=current_position[Z_AXIS];
current_position[Z_AXIS]+=retract_zlift;
destination[E_AXIS]=current_position[E_AXIS]+retract_length+retract_recover_length;
feedrate=retract_recover_feedrate;
retracted=false;
prepare_move();
}
break; break;
#endif //FWRETRACT #endif //FWRETRACT
case 28: //G28 Home all Axis one at a time case 28: //G28 Home all Axis one at a time
@ -1185,7 +1254,7 @@ void process_commands()
#else // NOT DELTA #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[X_AXIS])) || (code_seen(axis_codes[Y_AXIS])) || (code_seen(axis_codes[Z_AXIS])));
#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
if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) { if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
@ -1347,12 +1416,21 @@ void process_commands()
break; break;
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
case 29: // G29 Detailed Z-Probe, probes the bed at 3 points. case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more points.
{ {
#if Z_MIN_PIN == -1 #if Z_MIN_PIN == -1
#error "You must have a Z_MIN endstop in order to enable Auto Bed Leveling feature!!! Z_MIN_PIN must point to a valid hardware pin." #error "You must have a Z_MIN endstop in order to enable Auto Bed Leveling feature!!! Z_MIN_PIN must point to a valid hardware pin."
#endif #endif
// Prevent user from running a G29 without first homing in X and Y
if (! (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) )
{
LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN);
SERIAL_ECHO_START;
SERIAL_ECHOLNPGM(MSG_POSITION_UNKNOWN);
break; // abort G29, since we don't know where we are
}
st_synchronize(); st_synchronize();
// make sure the bed_level_rotation_matrix is identity or the planner will get it incorectly // make sure the bed_level_rotation_matrix is identity or the planner will get it incorectly
//vector_3 corrected_position = plan_get_position_mm(); //vector_3 corrected_position = plan_get_position_mm();
@ -1367,10 +1445,11 @@ void process_commands()
setup_for_endstop_move(); setup_for_endstop_move();
feedrate = homing_feedrate[Z_AXIS]; feedrate = homing_feedrate[Z_AXIS];
#ifdef ACCURATE_BED_LEVELING #ifdef AUTO_BED_LEVELING_GRID
// probe at the points of a lattice grid
int xGridSpacing = (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION) / (ACCURATE_BED_LEVELING_POINTS-1); int xGridSpacing = (RIGHT_PROBE_BED_POSITION - LEFT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
int yGridSpacing = (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION) / (ACCURATE_BED_LEVELING_POINTS-1); int yGridSpacing = (BACK_PROBE_BED_POSITION - FRONT_PROBE_BED_POSITION) / (AUTO_BED_LEVELING_GRID_POINTS-1);
// solve the plane equation ax + by + d = z // solve the plane equation ax + by + d = z
@ -1380,9 +1459,9 @@ void process_commands()
// so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z // so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z
// "A" matrix of the linear system of equations // "A" matrix of the linear system of equations
double eqnAMatrix[ACCURATE_BED_LEVELING_POINTS*ACCURATE_BED_LEVELING_POINTS*3]; double eqnAMatrix[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS*3];
// "B" vector of Z points // "B" vector of Z points
double eqnBVector[ACCURATE_BED_LEVELING_POINTS*ACCURATE_BED_LEVELING_POINTS]; double eqnBVector[AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS];
int probePointCounter = 0; int probePointCounter = 0;
@ -1405,37 +1484,26 @@ void process_commands()
zig = true; zig = true;
} }
for (int xCount=0; xCount < ACCURATE_BED_LEVELING_POINTS; xCount++) for (int xCount=0; xCount < AUTO_BED_LEVELING_GRID_POINTS; xCount++)
{ {
float z_before;
if (probePointCounter == 0) if (probePointCounter == 0)
{ {
// raise before probing // raise before probing
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], Z_RAISE_BEFORE_PROBING); z_before = Z_RAISE_BEFORE_PROBING;
} else } else
{ {
// raise extruder // raise extruder
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS); z_before = current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS;
} }
float measured_z = probe_pt(xProbe, yProbe, z_before);
do_blocking_move_to(xProbe - X_PROBE_OFFSET_FROM_EXTRUDER, yProbe - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]); eqnBVector[probePointCounter] = measured_z;
engage_z_probe(); // Engage Z Servo endstop if available eqnAMatrix[probePointCounter + 0*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = xProbe;
run_z_probe(); eqnAMatrix[probePointCounter + 1*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = yProbe;
eqnBVector[probePointCounter] = current_position[Z_AXIS]; eqnAMatrix[probePointCounter + 2*AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS] = 1;
retract_z_probe();
SERIAL_PROTOCOLPGM("Bed x: ");
SERIAL_PROTOCOL(xProbe);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL(yProbe);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM("\n");
eqnAMatrix[probePointCounter + 0*ACCURATE_BED_LEVELING_POINTS*ACCURATE_BED_LEVELING_POINTS] = xProbe;
eqnAMatrix[probePointCounter + 1*ACCURATE_BED_LEVELING_POINTS*ACCURATE_BED_LEVELING_POINTS] = yProbe;
eqnAMatrix[probePointCounter + 2*ACCURATE_BED_LEVELING_POINTS*ACCURATE_BED_LEVELING_POINTS] = 1;
probePointCounter++; probePointCounter++;
xProbe += xInc; xProbe += xInc;
} }
@ -1443,7 +1511,7 @@ void process_commands()
clean_up_after_endstop_move(); clean_up_after_endstop_move();
// solve lsq problem // solve lsq problem
double *plane_equation_coefficients = qr_solve(ACCURATE_BED_LEVELING_POINTS*ACCURATE_BED_LEVELING_POINTS, 3, eqnAMatrix, eqnBVector); double *plane_equation_coefficients = qr_solve(AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS, 3, eqnAMatrix, eqnBVector);
SERIAL_PROTOCOLPGM("Eqn coefficients: a: "); SERIAL_PROTOCOLPGM("Eqn coefficients: a: ");
SERIAL_PROTOCOL(plane_equation_coefficients[0]); SERIAL_PROTOCOL(plane_equation_coefficients[0]);
@ -1457,67 +1525,24 @@ void process_commands()
free(plane_equation_coefficients); free(plane_equation_coefficients);
#else // ACCURATE_BED_LEVELING not defined #else // AUTO_BED_LEVELING_GRID not defined
// Probe at 3 arbitrary points
// probe 1
float z_at_pt_1 = probe_pt(ABL_PROBE_PT_1_X, ABL_PROBE_PT_1_Y, Z_RAISE_BEFORE_PROBING);
// prob 1 // probe 2
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], Z_RAISE_BEFORE_PROBING); float z_at_pt_2 = probe_pt(ABL_PROBE_PT_2_X, ABL_PROBE_PT_2_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
do_blocking_move_to(LEFT_PROBE_BED_POSITION - X_PROBE_OFFSET_FROM_EXTRUDER, BACK_PROBE_BED_POSITION - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
engage_z_probe(); // Engage Z Servo endstop if available // probe 3
run_z_probe(); float z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
float z_at_xLeft_yBack = current_position[Z_AXIS];
retract_z_probe();
SERIAL_PROTOCOLPGM("Bed x: ");
SERIAL_PROTOCOL(LEFT_PROBE_BED_POSITION);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL(BACK_PROBE_BED_POSITION);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM("\n");
// prob 2
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
do_blocking_move_to(LEFT_PROBE_BED_POSITION - X_PROBE_OFFSET_FROM_EXTRUDER, FRONT_PROBE_BED_POSITION - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
engage_z_probe(); // Engage Z Servo endstop if available
run_z_probe();
float z_at_xLeft_yFront = current_position[Z_AXIS];
retract_z_probe();
SERIAL_PROTOCOLPGM("Bed x: ");
SERIAL_PROTOCOL(LEFT_PROBE_BED_POSITION);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL(FRONT_PROBE_BED_POSITION);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM("\n");
// prob 3
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS);
// the current position will be updated by the blocking move so the head will not lower on this next call.
do_blocking_move_to(RIGHT_PROBE_BED_POSITION - X_PROBE_OFFSET_FROM_EXTRUDER, FRONT_PROBE_BED_POSITION - Y_PROBE_OFFSET_FROM_EXTRUDER, current_position[Z_AXIS]);
engage_z_probe(); // Engage Z Servo endstop if available
run_z_probe();
float z_at_xRight_yFront = current_position[Z_AXIS];
retract_z_probe(); // Retract Z Servo endstop if available
SERIAL_PROTOCOLPGM("Bed x: ");
SERIAL_PROTOCOL(RIGHT_PROBE_BED_POSITION);
SERIAL_PROTOCOLPGM(" y: ");
SERIAL_PROTOCOL(FRONT_PROBE_BED_POSITION);
SERIAL_PROTOCOLPGM(" z: ");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM("\n");
clean_up_after_endstop_move(); clean_up_after_endstop_move();
set_bed_level_equation(z_at_xLeft_yFront, z_at_xRight_yFront, z_at_xLeft_yBack); set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3);
#endif // ACCURATE_BED_LEVELING #endif // AUTO_BED_LEVELING_GRID
st_synchronize(); st_synchronize();
// The following code correct the Z height difference from z-probe position and hotend tip position. // The following code correct the Z height difference from z-probe position and hotend tip position.
@ -1545,7 +1570,8 @@ void process_commands()
feedrate = homing_feedrate[Z_AXIS]; feedrate = homing_feedrate[Z_AXIS];
run_z_probe(); run_z_probe();
SERIAL_PROTOCOLPGM("Bed Position X: "); SERIAL_PROTOCOLPGM(MSG_BED);
SERIAL_PROTOCOLPGM(" X: ");
SERIAL_PROTOCOL(current_position[X_AXIS]); SERIAL_PROTOCOL(current_position[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y: "); SERIAL_PROTOCOLPGM(" Y: ");
SERIAL_PROTOCOL(current_position[Y_AXIS]); SERIAL_PROTOCOL(current_position[Y_AXIS]);
@ -2085,7 +2111,7 @@ void process_commands()
} }
else else
{ {
bool all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2]))|| (code_seen(axis_codes[3]))); bool all_axis = !((code_seen(axis_codes[X_AXIS])) || (code_seen(axis_codes[Y_AXIS])) || (code_seen(axis_codes[Z_AXIS]))|| (code_seen(axis_codes[E_AXIS])));
if(all_axis) if(all_axis)
{ {
st_synchronize(); st_synchronize();
@ -2286,6 +2312,19 @@ void process_commands()
} }
break; break;
#ifdef DELTA #ifdef DELTA
case 665: // M665 set delta configurations L<diagonal_rod> R<delta_radius> S<segments_per_sec>
if(code_seen('L')) {
delta_diagonal_rod= code_value();
}
if(code_seen('R')) {
delta_radius= code_value();
}
if(code_seen('S')) {
delta_segments_per_second= code_value();
}
recalc_delta_settings(delta_radius, delta_diagonal_rod);
break;
case 666: // M666 set delta endstop adjustemnt case 666: // M666 set delta endstop adjustemnt
for(int8_t i=0; i < 3; i++) for(int8_t i=0; i < 3; i++)
{ {
@ -2555,6 +2594,15 @@ void process_commands()
#endif //PIDTEMP #endif //PIDTEMP
case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/ case 240: // M240 Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
{ {
#ifdef CHDK
SET_OUTPUT(CHDK);
WRITE(CHDK, HIGH);
chdkHigh = millis();
chdkActive = true;
#else
#if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1 #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
const uint8_t NUM_PULSES=16; const uint8_t NUM_PULSES=16;
const float PULSE_LENGTH=0.01524; const float PULSE_LENGTH=0.01524;
@ -2572,6 +2620,7 @@ void process_commands()
_delay_ms(PULSE_LENGTH); _delay_ms(PULSE_LENGTH);
} }
#endif #endif
#endif //chdk end if
} }
break; break;
#ifdef DOGLCD #ifdef DOGLCD
@ -3041,42 +3090,6 @@ void get_coordinates()
next_feedrate = code_value(); next_feedrate = code_value();
if(next_feedrate > 0.0) feedrate = next_feedrate; if(next_feedrate > 0.0) feedrate = next_feedrate;
} }
#ifdef FWRETRACT
if(autoretract_enabled)
if( !(seen[X_AXIS] || seen[Y_AXIS] || seen[Z_AXIS]) && seen[E_AXIS])
{
float echange=destination[E_AXIS]-current_position[E_AXIS];
if(echange<-MIN_RETRACT) //retract
{
if(!retracted)
{
destination[Z_AXIS]+=retract_zlift; //not sure why chaninging current_position negatively does not work.
//if slicer retracted by echange=-1mm and you want to retract 3mm, corrrectede=-2mm additionally
float correctede=-echange-retract_length;
//to generate the additional steps, not the destination is changed, but inversely the current position
current_position[E_AXIS]+=-correctede;
feedrate=retract_feedrate;
retracted=true;
}
}
else
if(echange>MIN_RETRACT) //retract_recover
{
if(retracted)
{
//current_position[Z_AXIS]+=-retract_zlift;
//if slicer retracted_recovered by echange=+1mm and you want to retract_recover 3mm, corrrectede=2mm additionally
float correctede=-echange+1*retract_length+retract_recover_length; //total unretract=retract_length+retract_recover_length[surplus]
current_position[E_AXIS]+=correctede; //to generate the additional steps, not the destination is changed, but inversely the current position
feedrate=retract_recover_feedrate;
retracted=false;
}
}
}
#endif //FWRETRACT
} }
void get_arc_coordinates() void get_arc_coordinates()
@ -3120,19 +3133,30 @@ void clamp_to_software_endstops(float target[3])
} }
#ifdef DELTA #ifdef DELTA
void recalc_delta_settings(float radius, float diagonal_rod)
{
delta_tower1_x= -SIN_60*radius; // front left tower
delta_tower1_y= -COS_60*radius;
delta_tower2_x= SIN_60*radius; // front right tower
delta_tower2_y= -COS_60*radius;
delta_tower3_x= 0.0; // back middle tower
delta_tower3_y= radius;
delta_diagonal_rod_2= sq(diagonal_rod);
}
void calculate_delta(float cartesian[3]) void calculate_delta(float cartesian[3])
{ {
delta[X_AXIS] = sqrt(DELTA_DIAGONAL_ROD_2 delta[X_AXIS] = sqrt(delta_diagonal_rod_2
- sq(DELTA_TOWER1_X-cartesian[X_AXIS]) - sq(delta_tower1_x-cartesian[X_AXIS])
- sq(DELTA_TOWER1_Y-cartesian[Y_AXIS]) - sq(delta_tower1_y-cartesian[Y_AXIS])
) + cartesian[Z_AXIS]; ) + cartesian[Z_AXIS];
delta[Y_AXIS] = sqrt(DELTA_DIAGONAL_ROD_2 delta[Y_AXIS] = sqrt(delta_diagonal_rod_2
- sq(DELTA_TOWER2_X-cartesian[X_AXIS]) - sq(delta_tower2_x-cartesian[X_AXIS])
- sq(DELTA_TOWER2_Y-cartesian[Y_AXIS]) - sq(delta_tower2_y-cartesian[Y_AXIS])
) + cartesian[Z_AXIS]; ) + cartesian[Z_AXIS];
delta[Z_AXIS] = sqrt(DELTA_DIAGONAL_ROD_2 delta[Z_AXIS] = sqrt(delta_diagonal_rod_2
- sq(DELTA_TOWER3_X-cartesian[X_AXIS]) - sq(delta_tower3_x-cartesian[X_AXIS])
- sq(DELTA_TOWER3_Y-cartesian[Y_AXIS]) - sq(delta_tower3_y-cartesian[Y_AXIS])
) + cartesian[Z_AXIS]; ) + cartesian[Z_AXIS];
/* /*
SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]); SERIAL_ECHOPGM("cartesian x="); SERIAL_ECHO(cartesian[X_AXIS]);
@ -3162,7 +3186,7 @@ void prepare_move()
if (cartesian_mm < 0.000001) { cartesian_mm = abs(difference[E_AXIS]); } if (cartesian_mm < 0.000001) { cartesian_mm = abs(difference[E_AXIS]); }
if (cartesian_mm < 0.000001) { return; } if (cartesian_mm < 0.000001) { return; }
float seconds = 6000 * cartesian_mm / feedrate / feedmultiply; float seconds = 6000 * cartesian_mm / feedrate / feedmultiply;
int steps = max(1, int(DELTA_SEGMENTS_PER_SECOND * seconds)); int steps = max(1, int(delta_segments_per_second * seconds));
// SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm); // SERIAL_ECHOPGM("mm="); SERIAL_ECHO(cartesian_mm);
// SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds); // SERIAL_ECHOPGM(" seconds="); SERIAL_ECHO(seconds);
// SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps); // SERIAL_ECHOPGM(" steps="); SERIAL_ECHOLN(steps);
@ -3345,6 +3369,16 @@ void manage_inactivity()
} }
} }
} }
#ifdef CHDK //Check if pin should be set to LOW after M240 set it to HIGH
if (chdkActive)
{
chdkActive = false;
if (millis()-chdkHigh < CHDK_DELAY) return;
WRITE(CHDK, LOW);
}
#endif
#if defined(KILL_PIN) && KILL_PIN > -1 #if defined(KILL_PIN) && KILL_PIN > -1
if( 0 == READ(KILL_PIN) ) if( 0 == READ(KILL_PIN) )
kill(); kill();

Binary file not shown.

View File

@ -24,7 +24,7 @@
Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached. Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four. Timers are seized as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
The sequence used to sieze timers is defined in timers.h The sequence used to seize timers is defined in timers.h
The methods are: The methods are:
@ -50,7 +50,7 @@
/* /*
* Defines for 16 bit timers used with Servo library * Defines for 16 bit timers used with Servo library
* *
* If _useTimerX is defined then TimerX is a 16 bit timer on the curent board * If _useTimerX is defined then TimerX is a 16 bit timer on the current board
* timer16_Sequence_t enumerates the sequence that the timers should be allocated * timer16_Sequence_t enumerates the sequence that the timers should be allocated
* _Nbr_16timers indicates how many 16 bit timers are available. * _Nbr_16timers indicates how many 16 bit timers are available.
* *
@ -94,7 +94,7 @@ typedef enum { _Nbr_16timers } timer16_Sequence_t ;
#define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo #define MIN_PULSE_WIDTH 544 // the shortest pulse sent to a servo
#define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo #define MAX_PULSE_WIDTH 2400 // the longest pulse sent to a servo
#define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached #define DEFAULT_PULSE_WIDTH 1500 // default pulse width when servo is attached
#define REFRESH_INTERVAL 20000 // minumim time to refresh servos in microseconds #define REFRESH_INTERVAL 20000 // minimum time to refresh servos in microseconds
#define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer #define SERVOS_PER_TIMER 12 // the maximum number of servos controlled by one timer
#define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER) #define MAX_SERVOS (_Nbr_16timers * SERVOS_PER_TIMER)
@ -118,13 +118,13 @@ public:
uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure uint8_t attach(int pin); // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure
uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes. uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes.
void detach(); void detach();
void write(int value); // if value is < 200 its treated as an angle, otherwise as pulse width in microseconds void write(int value); // if value is < 200 it is treated as an angle, otherwise as pulse width in microseconds
void writeMicroseconds(int value); // Write pulse width in microseconds void writeMicroseconds(int value); // Write pulse width in microseconds
int read(); // returns current pulse width as an angle between 0 and 180 degrees int read(); // returns current pulse width as an angle between 0 and 180 degrees
int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release) int readMicroseconds(); // returns current pulse width in microseconds for this servo (was read_us() in first release)
bool attached(); // return true if this servo is attached, otherwise false bool attached(); // return true if this servo is attached, otherwise false
#if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0) #if defined (ENABLE_AUTO_BED_LEVELING) && (PROBE_SERVO_DEACTIVATION_DELAY > 0)
int pin; // store the hw pin of the servo int pin; // store the hardware pin of the servo
#endif #endif
private: private:
uint8_t servoIndex; // index into the channel data for this servo uint8_t servoIndex; // index into the channel data for this servo

View File

@ -22,7 +22,7 @@ CardReader::CardReader()
file_subcall_ctr=0; file_subcall_ctr=0;
memset(workDirParents, 0, sizeof(workDirParents)); 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 enough to make contact with the host software.
lastnr=0; lastnr=0;
//power to SD reader //power to SD reader
#if SDPOWER > -1 #if SDPOWER > -1
@ -245,7 +245,7 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
{ {
if(!cardOK) if(!cardOK)
return; return;
if(file.isOpen()) //replaceing current file by new file, or subfile call if(file.isOpen()) //replacing current file by new file, or subfile call
{ {
if(!replace_current) if(!replace_current)
{ {
@ -544,7 +544,7 @@ void CardReader::closefile(bool store_location)
if(store_location) if(store_location)
{ {
//future: store printer state, filename and position for continueing a stoped print //future: store printer state, filename and position for continuing a stopped print
// so one can unplug the printer and continue printing the next day. // so one can unplug the printer and continue printing the next day.
} }

View File

@ -16,9 +16,9 @@ Usage: python createTemperatureLookup.py [options]
Options: Options:
-h, --help show this help -h, --help show this help
--rp=... pull-up resistor --rp=... pull-up resistor
--t0=ttt:rrr low temperature temperature:resistance point (around 25C) --t1=ttt:rrr low temperature temperature:resistance point (around 25C)
--t1=ttt:rrr middle temperature temperature:resistance point (around 150C) --t2=ttt:rrr middle temperature temperature:resistance point (around 150C)
--t2=ttt:rrr high temperature temperature:resistance point (around 250C) --t3=ttt:rrr high temperature temperature:resistance point (around 250C)
--num-temps=... the number of temperature points to calculate (default: 20) --num-temps=... the number of temperature points to calculate (default: 20)
""" """
@ -98,7 +98,8 @@ def main(argv):
try: try:
opts, args = getopt.getopt(argv, "h", ["help", "rp=", "t1=", "t2=", "t3=", "num-temps="]) opts, args = getopt.getopt(argv, "h", ["help", "rp=", "t1=", "t2=", "t3=", "num-temps="])
except getopt.GetoptError: except getopt.GetoptError as err:
print str(err)
usage() usage()
sys.exit(2) sys.exit(2)

View File

@ -51,6 +51,7 @@
// 65 = Azteeg X1 // 65 = Azteeg X1
// 66 = Melzi with ATmega1284 (MaKr3d version) // 66 = Melzi with ATmega1284 (MaKr3d version)
// 67 = Azteeg X3 // 67 = Azteeg X3
// 68 = Azteeg X3 Pro
// 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 // 77 = 3Drag Controller
@ -119,18 +120,6 @@
// Effective horizontal distance bridged by diagonal push rods. // Effective horizontal distance bridged by diagonal push rods.
#define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET-DELTA_EFFECTOR_OFFSET-DELTA_CARRIAGE_OFFSET) #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET-DELTA_EFFECTOR_OFFSET-DELTA_CARRIAGE_OFFSET)
#define DELTA_DIAGONAL_ROD_2 sq(DELTA_DIAGONAL_ROD)
// 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 ============================
//=========================================================================== //===========================================================================

View File

@ -270,6 +270,12 @@
// Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards) // Motor Current setting (Only functional when motor driver current ref pins are connected to a digital trimpot on supported boards)
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) #define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
// uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro
//#define DIGIPOT_I2C
// Number of channels available for I2C digipot, For Azteeg X3 Pro we have 8
#define DIGIPOT_I2C_NUM_CHANNELS 8
// actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS
#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0}
//=========================================================================== //===========================================================================
//=============================Additional Features=========================== //=============================Additional Features===========================

View File

@ -1,5 +1,5 @@
/* /*
This code contibuted by Triffid_Hunter and modified by Kliment This code contributed by Triffid_Hunter and modified by Kliment
why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
*/ */

View File

@ -17,6 +17,7 @@
// 8 Portuguese // 8 Portuguese
// 9 Finnish // 9 Finnish
// 10 Aragonese // 10 Aragonese
// 11 Dutch
#ifndef LANGUAGE_CHOICE #ifndef LANGUAGE_CHOICE
#define LANGUAGE_CHOICE 1 // Pick your language from the list above #define LANGUAGE_CHOICE 1 // Pick your language from the list above
@ -54,27 +55,37 @@
#define STRINGIFY(n) STRINGIFY_(n) #define STRINGIFY(n) STRINGIFY_(n)
// Common LCD messages
/* nothing here as of yet */
// Common serial messages
#define MSG_MARLIN "Marlin"
#if LANGUAGE_CHOICE == 1 #if LANGUAGE_CHOICE == 1
// LCD Menu Messages // LCD Menu Messages
#define WELCOME_MSG MACHINE_NAME " Ready." // Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " ready."
#define MSG_SD_INSERTED "Card inserted" #define MSG_SD_INSERTED "Card inserted"
#define MSG_SD_REMOVED "Card removed" #define MSG_SD_REMOVED "Card removed"
#define MSG_MAIN "Main" #define MSG_MAIN "Main"
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Disable Steppers" #define MSG_DISABLE_STEPPERS "Disable steppers"
#define MSG_AUTO_HOME "Auto Home" #define MSG_AUTO_HOME "Auto home"
#define MSG_SET_ORIGIN "Set Origin" #define MSG_SET_ORIGIN "Set origin"
#define MSG_PREHEAT_PLA "Preheat PLA" #define MSG_PREHEAT_PLA "Preheat PLA"
#define MSG_PREHEAT_PLA_SETTINGS "Preheat PLA Conf" #define MSG_PREHEAT_PLA_SETTINGS "Preheat PLA conf"
#define MSG_PREHEAT_ABS "Preheat ABS" #define MSG_PREHEAT_ABS "Preheat ABS"
#define MSG_PREHEAT_ABS_SETTINGS "Preheat ABS Conf" #define MSG_PREHEAT_ABS_SETTINGS "Preheat ABS conf"
#define MSG_COOLDOWN "Cooldown" #define MSG_COOLDOWN "Cooldown"
#define MSG_SWITCH_PS_ON "Switch Power On" #define MSG_SWITCH_PS_ON "Switch power on"
#define MSG_SWITCH_PS_OFF "Switch Power Off" #define MSG_SWITCH_PS_OFF "Switch power off"
#define MSG_EXTRUDE "Extrude" #define MSG_EXTRUDE "Extrude"
#define MSG_RETRACT "Retract" #define MSG_RETRACT "Retract"
#define MSG_MOVE_AXIS "Move Axis" #define MSG_MOVE_AXIS "Move axis"
#define MSG_MOVE_X "Move X" #define MSG_MOVE_X "Move X"
#define MSG_MOVE_Y "Move Y" #define MSG_MOVE_Y "Move Y"
#define MSG_MOVE_Z "Move Z" #define MSG_MOVE_Z "Move Z"
@ -123,16 +134,16 @@
#define MSG_CONTRAST "LCD contrast" #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"
#define MSG_REFRESH "Refresh" #define MSG_REFRESH "Refresh"
#define MSG_WATCH "Info screen" #define MSG_WATCH "Info screen"
#define MSG_PREPARE "Prepare" #define MSG_PREPARE "Prepare"
#define MSG_TUNE "Tune" #define MSG_TUNE "Tune"
#define MSG_PAUSE_PRINT "Pause Print" #define MSG_PAUSE_PRINT "Pause print"
#define MSG_RESUME_PRINT "Resume Print" #define MSG_RESUME_PRINT "Resume print"
#define MSG_STOP_PRINT "Stop Print" #define MSG_STOP_PRINT "Stop print"
#define MSG_CARD_MENU "Print from SD" #define MSG_CARD_MENU "Print from SD"
#define MSG_NO_CARD "No Card" #define MSG_NO_CARD "No SD card"
#define MSG_DWELL "Sleep..." #define MSG_DWELL "Sleep..."
#define MSG_USERWAIT "Wait for user..." #define MSG_USERWAIT "Wait for user..."
#define MSG_RESUMING "Resuming print" #define MSG_RESUMING "Resuming print"
@ -146,16 +157,15 @@
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet F" #define MSG_CONTROL_RETRACT_RECOVERF "UnRet F"
#define MSG_AUTORETRACT "AutoRetr." #define MSG_AUTORETRACT "AutoRetr."
#define MSG_FILAMENTCHANGE "Change filament" #define MSG_FILAMENTCHANGE "Change filament"
#define MSG_INIT_SDCARD "Init. SD-Card" #define MSG_INIT_SDCARD "Init. SD card"
#define MSG_CNG_SDCARD "Change SD-Card" #define MSG_CNG_SDCARD "Change SD card"
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y" #define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z" #define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort" #define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_CONTRAST "Contrast"
// Serial Console Messages // Serial Console Messages
@ -165,7 +175,6 @@
#define MSG_BROWNOUT_RESET " Brown out Reset" #define MSG_BROWNOUT_RESET " Brown out Reset"
#define MSG_WATCHDOG_RESET " Watchdog Reset" #define MSG_WATCHDOG_RESET " Watchdog Reset"
#define MSG_SOFTWARE_RESET " Software Reset" #define MSG_SOFTWARE_RESET " Software Reset"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Author: " #define MSG_AUTHOR " | Author: "
#define MSG_CONFIGURATION_VER " Last Updated: " #define MSG_CONFIGURATION_VER " Last Updated: "
#define MSG_FREE_MEMORY " Free Memory: " #define MSG_FREE_MEMORY " Free Memory: "
@ -231,13 +240,17 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#endif #endif
#if LANGUAGE_CHOICE == 2 #if LANGUAGE_CHOICE == 2
// LCD Menu Messages // LCD Menu Messages
// Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " gotowy." #define WELCOME_MSG MACHINE_NAME " gotowy."
#define MSG_SD_INSERTED "Karta wlozona" #define MSG_SD_INSERTED "Karta wlozona"
#define MSG_SD_REMOVED "Karta usunieta" #define MSG_SD_REMOVED "Karta usunieta"
@ -245,11 +258,11 @@
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Wylacz silniki" #define MSG_DISABLE_STEPPERS "Wylacz silniki"
#define MSG_AUTO_HOME "Auto. poz. zerowa" #define MSG_AUTO_HOME "Auto. poz. zerowa"
#define MSG_SET_ORIGIN "Ustaw punkt zerowy" #define MSG_SET_ORIGIN "Ustaw punkt zero"
#define MSG_PREHEAT_PLA "Rozgrzej PLA" #define MSG_PREHEAT_PLA "Rozgrzej PLA"
#define MSG_PREHEAT_PLA_SETTINGS "Ustawienia roz. PLA" #define MSG_PREHEAT_PLA_SETTINGS "Ustaw. rozg. PLA"
#define MSG_PREHEAT_ABS "Rozgrzej ABS" #define MSG_PREHEAT_ABS "Rozgrzej ABS"
#define MSG_PREHEAT_ABS_SETTINGS "Ustawienia roz. ABS" #define MSG_PREHEAT_ABS_SETTINGS "Ustaw. rozg. ABS"
#define MSG_COOLDOWN "Chlodzenie" #define MSG_COOLDOWN "Chlodzenie"
#define MSG_SWITCH_PS_ON "Wlacz zasilacz" #define MSG_SWITCH_PS_ON "Wlacz zasilacz"
#define MSG_SWITCH_PS_OFF "Wylacz zasilacz" #define MSG_SWITCH_PS_OFF "Wylacz zasilacz"
@ -260,7 +273,7 @@
#define MSG_MOVE_Y "Przesun w Y" #define MSG_MOVE_Y "Przesun w Y"
#define MSG_MOVE_Z "Przesun w Z" #define MSG_MOVE_Z "Przesun w Z"
#define MSG_MOVE_E "Ekstruzja (os E)" #define MSG_MOVE_E "Ekstruzja (os E)"
#define MSG_MOVE_01MM "Przesuwaj co 0.1mm" #define MSG_MOVE_01MM "Przesuwaj co .1mm"
#define MSG_MOVE_1MM "Przesuwaj co 1mm" #define MSG_MOVE_1MM "Przesuwaj co 1mm"
#define MSG_MOVE_10MM "Przesuwaj co 10mm" #define MSG_MOVE_10MM "Przesuwaj co 10mm"
#define MSG_SPEED "Predkosc" #define MSG_SPEED "Predkosc"
@ -304,7 +317,7 @@
#define MSG_CONTRAST "Kontrast LCD" #define MSG_CONTRAST "Kontrast LCD"
#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 "Ustaw. fabryczne"
#define MSG_REFRESH "\004Odswiez" #define MSG_REFRESH "\004Odswiez"
#define MSG_WATCH "Ekran glowny" #define MSG_WATCH "Ekran glowny"
#define MSG_PREPARE "Przygotuj" #define MSG_PREPARE "Przygotuj"
@ -316,10 +329,9 @@
#define MSG_CARD_MENU "Menu karty SD" #define MSG_CARD_MENU "Menu karty SD"
#define MSG_NO_CARD "Brak karty" #define MSG_NO_CARD "Brak karty"
#define MSG_DWELL "Uspij..." #define MSG_DWELL "Uspij..."
#define MSG_USERWAIT "Czekam na uzytkownika..." #define MSG_USERWAIT "Oczekiwanie..."
#define MSG_RESUMING "Wznawiam drukowanie" #define MSG_RESUMING "Wznawianie druku"
#define MSG_NO_MOVE "Brak ruchu." #define MSG_NO_MOVE "Brak ruchu"
#define MSG_PART_RELEASE "Czesciowe zwolnienie"
#define MSG_KILLED "Ubity. " #define MSG_KILLED "Ubity. "
#define MSG_STOPPED "Zatrzymany. " #define MSG_STOPPED "Zatrzymany. "
#define MSG_STEPPER_RELEASED "Zwolniony." #define MSG_STEPPER_RELEASED "Zwolniony."
@ -330,15 +342,15 @@
#define MSG_CONTROL_RETRACT_RECOVERF "Cof. wycof. F" #define MSG_CONTROL_RETRACT_RECOVERF "Cof. wycof. F"
#define MSG_AUTORETRACT "Auto. wycofanie" #define MSG_AUTORETRACT "Auto. wycofanie"
#define MSG_FILAMENTCHANGE "Zmien filament" #define MSG_FILAMENTCHANGE "Zmien filament"
#define MSG_INIT_SDCARD "Inicjalizacja karty" #define MSG_INIT_SDCARD "Inicjal. karty SD"
#define MSG_CNG_SDCARD "Zmiana karty SD" #define MSG_CNG_SDCARD "Zmiana karty SD"
#define MSG_ZPROBE_OUT "Probkuj Z poza lozem" #define MSG_ZPROBE_OUT "Sonda Z za lozem"
#define MSG_POSITION_UNKNOWN "Powrot w X/Y przed Z" #define MSG_POSITION_UNKNOWN "Wroc w XY przed Z"
#define MSG_ZPROBE_ZOFFSET "Offset Z" #define MSG_ZPROBE_ZOFFSET "Offset Z"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y" #define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z" #define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Blad wyl. krancowego" #define MSG_ENDSTOP_ABORT "Blad wyl. kranc."
#define MSG_CONTRAST "Kontrast" #define MSG_CONTRAST "Kontrast"
// Serial Console Messages // Serial Console Messages
@ -349,7 +361,6 @@
#define MSG_BROWNOUT_RESET " Reset (spadek napiecia)" #define MSG_BROWNOUT_RESET " Reset (spadek napiecia)"
#define MSG_WATCHDOG_RESET " Reset (watchdog)" #define MSG_WATCHDOG_RESET " Reset (watchdog)"
#define MSG_SOFTWARE_RESET " Reset (programowy)" #define MSG_SOFTWARE_RESET " Reset (programowy)"
#define MSG_MARLIN "Marlin"
#define MSG_AUTHOR " | Autor: " #define MSG_AUTHOR " | Autor: "
#define MSG_CONFIGURATION_VER " Ostatnia aktualizacja: " #define MSG_CONFIGURATION_VER " Ostatnia aktualizacja: "
#define MSG_FREE_MEMORY " Wolna pamiec: " #define MSG_FREE_MEMORY " Wolna pamiec: "
@ -415,12 +426,16 @@
#define MSG_BABYSTEPPING_X "Babystepping w osi X" #define MSG_BABYSTEPPING_X "Babystepping w osi X"
#define MSG_BABYSTEPPING_Y "Babystepping w osi Y" #define MSG_BABYSTEPPING_Y "Babystepping w osi Y"
#define MSG_BABYSTEPPING_Z "Babystepping w osi Z" #define MSG_BABYSTEPPING_Z "Babystepping w osi Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#endif #endif
#if LANGUAGE_CHOICE == 3 #if LANGUAGE_CHOICE == 3
// LCD Menu Messages
// Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " prete." #define WELCOME_MSG MACHINE_NAME " prete."
#define MSG_SD_INSERTED "Carte inseree" #define MSG_SD_INSERTED "Carte inseree"
#define MSG_SD_REMOVED "Carte retiree" #define MSG_SD_REMOVED "Carte retiree"
@ -430,9 +445,9 @@
#define MSG_AUTO_HOME "Home auto." #define MSG_AUTO_HOME "Home auto."
#define MSG_SET_ORIGIN "Regler origine" #define MSG_SET_ORIGIN "Regler origine"
#define MSG_PREHEAT_PLA " Prechauffage PLA" #define MSG_PREHEAT_PLA " Prechauffage PLA"
#define MSG_PREHEAT_PLA_SETTINGS " Regl. prechauffe PLA" #define MSG_PREHEAT_PLA_SETTINGS " Regl. prech. PLA"
#define MSG_PREHEAT_ABS "Prechauffage ABS" #define MSG_PREHEAT_ABS "Prechauffage ABS"
#define MSG_PREHEAT_ABS_SETTINGS "Regl. prechauffe ABS" #define MSG_PREHEAT_ABS_SETTINGS "Regl. prech. ABS"
#define MSG_COOLDOWN "Refroidir" #define MSG_COOLDOWN "Refroidir"
#define MSG_SWITCH_PS_ON "Allumer alim." #define MSG_SWITCH_PS_ON "Allumer alim."
#define MSG_SWITCH_PS_OFF "Eteindre alim." #define MSG_SWITCH_PS_OFF "Eteindre alim."
@ -453,7 +468,7 @@
#define MSG_NOZZLE1 "Buse2" #define MSG_NOZZLE1 "Buse2"
#define MSG_NOZZLE2 "Buse3" #define MSG_NOZZLE2 "Buse3"
#define MSG_BED "Plateau" #define MSG_BED "Plateau"
#define MSG_FAN_SPEED "Vitesse ventilateur" #define MSG_FAN_SPEED "Vite. ventilateur"
#define MSG_FLOW "Flux" #define MSG_FLOW "Flux"
#define MSG_CONTROL "Controler" #define MSG_CONTROL "Controler"
#define MSG_MIN " \002 Min" #define MSG_MIN " \002 Min"
@ -499,10 +514,9 @@
#define MSG_CARD_MENU "Impr. depuis SD" #define MSG_CARD_MENU "Impr. depuis SD"
#define MSG_NO_CARD "Pas de carte" #define MSG_NO_CARD "Pas de carte"
#define MSG_DWELL "Repos..." #define MSG_DWELL "Repos..."
#define MSG_USERWAIT "Attente de l'utilisateur..." #define MSG_USERWAIT "Atten. de l'util."
#define MSG_RESUMING "Reprise de l'impression" #define MSG_RESUMING "Repri. de l'impr."
#define MSG_NO_MOVE "Aucun mouvement." #define MSG_NO_MOVE "Aucun mouvement."
#define MSG_PART_RELEASE "Relache partielle"
#define MSG_KILLED "MORT." #define MSG_KILLED "MORT."
#define MSG_STOPPED "STOPPE." #define MSG_STOPPED "STOPPE."
#define MSG_STEPPER_RELEASED "RELACHE." #define MSG_STEPPER_RELEASED "RELACHE."
@ -514,14 +528,14 @@
#define MSG_AUTORETRACT "Retract. Auto." #define MSG_AUTORETRACT "Retract. Auto."
#define MSG_FILAMENTCHANGE "Changer filament" #define MSG_FILAMENTCHANGE "Changer filament"
#define MSG_INIT_SDCARD "Init. la carte SD" #define MSG_INIT_SDCARD "Init. la carte SD"
#define MSG_CNG_SDCARD "Changer de carte SD" #define MSG_CNG_SDCARD "Changer de carte"
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z sonde exte. lit"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Rev. dans XY av.Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Offset Z"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y" #define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z" #define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort" #define MSG_ENDSTOP_ABORT "Butee abandon"
#define MSG_CONTRAST "Contrast" #define MSG_CONTRAST "Contrast"
// Serial Console Messages // Serial Console Messages
@ -532,7 +546,6 @@
#define MSG_BROWNOUT_RESET " RAZ defaut alim." #define MSG_BROWNOUT_RESET " RAZ defaut alim."
#define MSG_WATCHDOG_RESET " RAZ Watchdog" #define MSG_WATCHDOG_RESET " RAZ Watchdog"
#define MSG_SOFTWARE_RESET " RAZ logicielle" #define MSG_SOFTWARE_RESET " RAZ logicielle"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Auteur: " #define MSG_AUTHOR " | Auteur: "
#define MSG_CONFIGURATION_VER " Derniere MaJ: " #define MSG_CONFIGURATION_VER " Derniere MaJ: "
#define MSG_FREE_MEMORY " Memoire libre: " #define MSG_FREE_MEMORY " Memoire libre: "
@ -598,6 +611,7 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#endif #endif
@ -605,6 +619,7 @@
#if LANGUAGE_CHOICE == 4 #if LANGUAGE_CHOICE == 4
// LCD Menu Messages // LCD Menu Messages
// Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " Bereit." #define WELCOME_MSG MACHINE_NAME " Bereit."
@ -612,13 +627,13 @@
#define MSG_SD_REMOVED "SDKarte entfernt" #define MSG_SD_REMOVED "SDKarte entfernt"
#define MSG_MAIN "Hauptmenü" #define MSG_MAIN "Hauptmenü"
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Stepper abschalten" #define MSG_DISABLE_STEPPERS "Stepper abschalt."
#define MSG_AUTO_HOME "Auto Nullpunkt" #define MSG_AUTO_HOME "Auto Nullpunkt"
#define MSG_SET_ORIGIN "Setze Nullpunkt" #define MSG_SET_ORIGIN "Setze Nullpunkt"
#define MSG_PREHEAT_PLA "Vorwärmen PLA" #define MSG_PREHEAT_PLA "Vorwärmen PLA"
#define MSG_PREHEAT_PLA_SETTINGS "Vorwärmen PLA Einstellungen" #define MSG_PREHEAT_PLA_SETTINGS "Vorwärm. PLA Ein."
#define MSG_PREHEAT_ABS "Vorwärmen ABS" #define MSG_PREHEAT_ABS "Vorwärmen ABS"
#define MSG_PREHEAT_ABS_SETTINGS "Vorwärmen ABS Einstellungen" #define MSG_PREHEAT_ABS_SETTINGS "Vorwärm. ABS Ein."
#define MSG_COOLDOWN "Abkühlen" #define MSG_COOLDOWN "Abkühlen"
#define MSG_SWITCH_PS_ON "Switch Power On" #define MSG_SWITCH_PS_ON "Switch Power On"
#define MSG_SWITCH_PS_OFF "Switch Power Off" #define MSG_SWITCH_PS_OFF "Switch Power Off"
@ -685,10 +700,9 @@
#define MSG_CARD_MENU "SDKarten Menü" #define MSG_CARD_MENU "SDKarten Menü"
#define MSG_NO_CARD "Keine SDKarte" #define MSG_NO_CARD "Keine SDKarte"
#define MSG_DWELL "Warten..." #define MSG_DWELL "Warten..."
#define MSG_USERWAIT "Warte auf Nutzer..." #define MSG_USERWAIT "Warte auf Nutzer"
#define MSG_RESUMING "Druck fortsetzung" #define MSG_RESUMING "Druck fortsetzung"
#define MSG_NO_MOVE "Kein Zug." #define MSG_NO_MOVE "Kein Zug."
#define MSG_PART_RELEASE "Stepper tlw frei"
#define MSG_KILLED "KILLED" #define MSG_KILLED "KILLED"
#define MSG_STOPPED "GESTOPPT" #define MSG_STOPPED "GESTOPPT"
#define MSG_STEPPER_RELEASED "Stepper frei" #define MSG_STEPPER_RELEASED "Stepper frei"
@ -701,7 +715,7 @@
#define MSG_FILAMENTCHANGE "Filament wechseln" #define MSG_FILAMENTCHANGE "Filament wechseln"
#define MSG_INIT_SDCARD "Init. SD-Card" #define MSG_INIT_SDCARD "Init. SD-Card"
#define MSG_CNG_SDCARD "Change SD-Card" #define MSG_CNG_SDCARD "Change SD-Card"
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
@ -718,7 +732,6 @@
#define MSG_BROWNOUT_RESET " Brown out Reset" #define MSG_BROWNOUT_RESET " Brown out Reset"
#define MSG_WATCHDOG_RESET " Watchdog Reset" #define MSG_WATCHDOG_RESET " Watchdog Reset"
#define MSG_SOFTWARE_RESET " Software Reset" #define MSG_SOFTWARE_RESET " Software Reset"
#define MSG_MARLIN "Marlin: "
#define MSG_AUTHOR " | Author: " #define MSG_AUTHOR " | Author: "
#define MSG_CONFIGURATION_VER " Last Updated: " #define MSG_CONFIGURATION_VER " Last Updated: "
#define MSG_FREE_MEMORY " Free Memory: " #define MSG_FREE_MEMORY " Free Memory: "
@ -784,6 +797,7 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#endif #endif
@ -791,14 +805,16 @@
#if LANGUAGE_CHOICE == 5 #if LANGUAGE_CHOICE == 5
// LCD Menu Messages // LCD Menu Messages
#define WELCOME_MSG MACHINE_NAME "Lista." // Please note these are limited to 17 characters!
#define MSG_SD_INSERTED "Tarjeta SD Colocada"
#define MSG_SD_REMOVED "Tarjeta SD Retirada" #define WELCOME_MSG MACHINE_NAME " lista."
#define MSG_MAIN "Menu Principal" #define MSG_SD_INSERTED "Tarjeta colocada"
#define MSG_SD_REMOVED "Tarjeta retirada"
#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 al Origen" // "Llevar Ejes al Cero" #define MSG_AUTO_HOME "Llevar al origen"
#define MSG_SET_ORIGIN "Establecer Cero" #define MSG_SET_ORIGIN "Establecer cero"
#define MSG_PREHEAT_PLA "Precalentar PLA" #define MSG_PREHEAT_PLA "Precalentar PLA"
#define MSG_PREHEAT_PLA_SETTINGS "Ajustar temp. PLA" #define MSG_PREHEAT_PLA_SETTINGS "Ajustar temp. PLA"
#define MSG_PREHEAT_ABS "Precalentar ABS" #define MSG_PREHEAT_ABS "Precalentar ABS"
@ -808,7 +824,7 @@
#define MSG_SWITCH_PS_OFF "Switch Power Off" #define MSG_SWITCH_PS_OFF "Switch Power Off"
#define MSG_EXTRUDE "Extruir" #define MSG_EXTRUDE "Extruir"
#define MSG_RETRACT "Retraer" #define MSG_RETRACT "Retraer"
#define MSG_MOVE_AXIS "Mover Ejes" #define MSG_MOVE_AXIS "Mover ejes"
#define MSG_MOVE_X "Move X" #define MSG_MOVE_X "Move X"
#define MSG_MOVE_Y "Move Y" #define MSG_MOVE_Y "Move Y"
#define MSG_MOVE_Z "Move Z" #define MSG_MOVE_Z "Move Z"
@ -854,24 +870,24 @@
#define MSG_RECTRACT "Retraer" #define MSG_RECTRACT "Retraer"
#define MSG_TEMPERATURE "Temperatura" #define MSG_TEMPERATURE "Temperatura"
#define MSG_MOTION "Movimiento" #define MSG_MOTION "Movimiento"
#define MSG_STORE_EPROM "Guardar Memoria" #define MSG_STORE_EPROM "Guardar memoria"
#define MSG_LOAD_EPROM "Cargar Memoria" #define MSG_LOAD_EPROM "Cargar memoria"
#define MSG_RESTORE_FAILSAFE "Rest. de emergencia" #define MSG_RESTORE_FAILSAFE "Rest. de emergen."
#define MSG_REFRESH "Volver a cargar" #define MSG_REFRESH "Volver a cargar"
#define MSG_WATCH "Monitorizar" #define MSG_WATCH "Monitorizar"
#define MSG_PREPARE "Preparar" #define MSG_PREPARE "Preparar"
#define MSG_TUNE "Ajustar" #define MSG_TUNE "Ajustar"
#define MSG_PAUSE_PRINT "Pausar Impresion" #define MSG_PAUSE_PRINT "Pausar impresion"
#define MSG_RESUME_PRINT "Reanudar Impresion" #define MSG_RESUME_PRINT "Reanudar impres."
#define MSG_STOP_PRINT "Detener Impresion" #define MSG_STOP_PRINT "Detener impresion"
#define MSG_CARD_MENU "Menu de SD" #define MSG_CARD_MENU "Menu de SD"
#define MSG_NO_CARD "No hay Tarjeta SD" #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_RESUMING "Resumiendo impre."
#define MSG_NO_MOVE "Sin movimiento" #define MSG_NO_MOVE "Sin movimiento"
#define MSG_KILLED "PARADA DE EMERGENCIA. " #define MSG_KILLED "PARADA DE EMERG."
#define MSG_STOPPED "PARADA." #define MSG_STOPPED "PARADA"
#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"
@ -879,19 +895,18 @@
#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_INIT_SDCARD "Iniciando tarjeta"
#define MSG_CNG_SDCARD "Cambiar Tarjeta-SD" #define MSG_CNG_SDCARD "Cambiar tarjeta"
#define MSG_RECTRACT_WIDE "Retraer" #define MSG_RECTRACT_WIDE "Retraer"
#define MSG_TEMPERATURE_WIDE "Temperatura" #define MSG_TEMPERATURE_WIDE "Temperatura"
#define MSG_TEMPERATURE_RTN "Temperatura" #define MSG_TEMPERATURE_RTN "Temperatura"
#define MSG_MAIN_WIDE "Menu Principal" #define MSG_MAIN_WIDE "Menu principal"
#define MSG_MOTION_WIDE "Movimiento" #define MSG_MOTION_WIDE "Movimiento"
#define MSG_PREPARE_ALT "Preparar" #define MSG_PREPARE_ALT "Preparar"
#define MSG_CONTROL_ARROW "Control" #define MSG_CONTROL_ARROW "Control"
#define MSG_RETRACT_ARROW "Retraer" #define MSG_RETRACT_ARROW "Retraer"
#define MSG_PART_RELEASE "Desacople Parcial"
#define MSG_STEPPER_RELEASED "Desacoplada." #define MSG_STEPPER_RELEASED "Desacoplada."
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
@ -908,7 +923,6 @@
#define MSG_BROWNOUT_RESET " Reset por Voltaje Incorrecto" #define MSG_BROWNOUT_RESET " Reset por Voltaje Incorrecto"
#define MSG_WATCHDOG_RESET " Reset por Bloqueo" #define MSG_WATCHDOG_RESET " Reset por Bloqueo"
#define MSG_SOFTWARE_RESET " Reset por Software" #define MSG_SOFTWARE_RESET " Reset por Software"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Autor: " #define MSG_AUTHOR " | Autor: "
#define MSG_CONFIGURATION_VER " Ultima actualizacion: " #define MSG_CONFIGURATION_VER " Ultima actualizacion: "
#define MSG_FREE_MEMORY " Memoria libre: " #define MSG_FREE_MEMORY " Memoria libre: "
@ -973,30 +987,34 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#endif #endif
#if LANGUAGE_CHOICE == 6 #if LANGUAGE_CHOICE == 6
// LCD Menu Messages // LCD Menu Messages
#define WELCOME_MSG MACHINE_NAME " Готов" // Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " Готов."
#define MSG_SD_INSERTED "Карта вставлена" #define MSG_SD_INSERTED "Карта вставлена"
#define MSG_SD_REMOVED "Карта извлечена" #define MSG_SD_REMOVED "Карта извлечена"
#define MSG_MAIN "Меню \003" #define MSG_MAIN "Меню \003"
#define MSG_AUTOSTART "Автостарт" #define MSG_AUTOSTART "Автостарт"
#define MSG_DISABLE_STEPPERS " Выключить двигатели" #define MSG_DISABLE_STEPPERS "Выкл. двигатели"
#define MSG_AUTO_HOME "Парковка" #define MSG_AUTO_HOME "Парковка"
#define MSG_SET_ORIGIN "Запомнить ноль" #define MSG_SET_ORIGIN "Запомнить ноль"
#define MSG_PREHEAT_PLA "Преднагрев PLA" #define MSG_PREHEAT_PLA "Преднагрев PLA"
#define MSG_PREHEAT_PLA_SETTINGS " Настр. преднагр.PLA" #define MSG_PREHEAT_PLA_SETTINGS "Настройки PLA"
#define MSG_PREHEAT_ABS "Преднагрев ABS" #define MSG_PREHEAT_ABS "Преднагрев ABS"
#define MSG_PREHEAT_ABS_SETTINGS " Настр. преднагр.ABS" #define MSG_PREHEAT_ABS_SETTINGS "Настройки ABS"
#define MSG_COOLDOWN "Охлаждение" #define MSG_COOLDOWN "Охлаждение"
#define MSG_SWITCH_PS_ON "Switch Power On" #define MSG_SWITCH_PS_ON "Switch Power On"
#define MSG_SWITCH_PS_OFF "Switch Power Off" #define MSG_SWITCH_PS_OFF "Switch Power Off"
#define MSG_EXTRUDE "Экструзия" #define MSG_EXTRUDE "Экструзия"
#define MSG_RETRACT "Откат" #define MSG_RETRACT "Откат"
#define MSG_MOVE_AXIS " Движение по осям \x7E" #define MSG_MOVE_AXIS "Движение по осям"
#define MSG_MOVE_X "Move X" #define MSG_MOVE_X "Move X"
#define MSG_MOVE_Y "Move Y" #define MSG_MOVE_Y "Move Y"
#define MSG_MOVE_Z "Move Z" #define MSG_MOVE_Z "Move Z"
@ -1043,23 +1061,22 @@
#define MSG_TEMPERATURE "Температура \x7E" #define MSG_TEMPERATURE "Температура \x7E"
#define MSG_MOTION "Скорости \x7E" #define MSG_MOTION "Скорости \x7E"
#define MSG_CONTRAST "LCD contrast" #define MSG_CONTRAST "LCD contrast"
#define MSG_STORE_EPROM " Сохранить настройки" #define MSG_STORE_EPROM "Сохранить в EPROM"
#define MSG_LOAD_EPROM " Загрузить настройки" #define MSG_LOAD_EPROM "Загруз. из EPROM"
#define MSG_RESTORE_FAILSAFE "Сброс настроек" #define MSG_RESTORE_FAILSAFE "Сброс настроек"
#define MSG_REFRESH "\004Обновить" #define MSG_REFRESH "\004Обновить"
#define MSG_WATCH "Обзор \003" #define MSG_WATCH "Обзор \003"
#define MSG_PREPARE "Действия \x7E" #define MSG_PREPARE "Действия \x7E"
#define MSG_TUNE "Настройки \x7E" #define MSG_TUNE "Настройки \x7E"
#define MSG_PAUSE_PRINT " Пауза печати \x7E" #define MSG_RESUME_PRINT "Продолжить печать"
#define MSG_RESUME_PRINT " Продолжить печать \x7E" #define MSG_RESUME_PRINT "Продолжить печать"
#define MSG_STOP_PRINT " Остановить печать \x7E" #define MSG_STOP_PRINT "Остановить печать"
#define MSG_CARD_MENU "Меню карты \x7E" #define MSG_CARD_MENU "Меню карты \x7E"
#define MSG_NO_CARD "Нет карты" #define MSG_NO_CARD "Нет карты"
#define MSG_DWELL "Сон..." #define MSG_DWELL "Сон..."
#define MSG_USERWAIT "Нажмите для продолж." #define MSG_USERWAIT "Ожиданиие"
#define MSG_RESUMING "Resuming print" #define MSG_RESUMING "Resuming print"
#define MSG_NO_MOVE "Нет движения." #define MSG_NO_MOVE "Нет движения."
#define MSG_PART_RELEASE " Извлечение принта "
#define MSG_KILLED "УБИТО." #define MSG_KILLED "УБИТО."
#define MSG_STOPPED "ОСТАНОВЛЕНО." #define MSG_STOPPED "ОСТАНОВЛЕНО."
#define MSG_CONTROL_RETRACT "Откат mm:" #define MSG_CONTROL_RETRACT "Откат mm:"
@ -1071,7 +1088,7 @@
#define MSG_FILAMENTCHANGE "Change filament" #define MSG_FILAMENTCHANGE "Change filament"
#define MSG_INIT_SDCARD "Init. SD-Card" #define MSG_INIT_SDCARD "Init. SD-Card"
#define MSG_CNG_SDCARD "Change SD-Card" #define MSG_CNG_SDCARD "Change SD-Card"
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
@ -1088,7 +1105,6 @@
#define MSG_BROWNOUT_RESET " Brown out сброс" #define MSG_BROWNOUT_RESET " Brown out сброс"
#define MSG_WATCHDOG_RESET " Watchdog сброс" #define MSG_WATCHDOG_RESET " Watchdog сброс"
#define MSG_SOFTWARE_RESET " программный сброс" #define MSG_SOFTWARE_RESET " программный сброс"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Автор: " #define MSG_AUTHOR " | Автор: "
#define MSG_CONFIGURATION_VER " Последнее обновление: " #define MSG_CONFIGURATION_VER " Последнее обновление: "
#define MSG_FREE_MEMORY " Памяти свободно: " #define MSG_FREE_MEMORY " Памяти свободно: "
@ -1152,6 +1168,7 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#endif #endif
@ -1159,7 +1176,9 @@
#if LANGUAGE_CHOICE == 7 #if LANGUAGE_CHOICE == 7
// LCD Menu Messages // LCD Menu Messages
#define WELCOME_MSG MACHINE_NAME " Pronta" // Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " pronto."
#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"
@ -1247,11 +1266,10 @@
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm" #define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet F" #define MSG_CONTROL_RETRACT_RECOVERF "UnRet F"
#define MSG_AUTORETRACT "AutoArretramento" #define MSG_AUTORETRACT "AutoArretramento"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Qualcosa non va in MenuStructure."
#define MSG_FILAMENTCHANGE "Cambia filamento" #define MSG_FILAMENTCHANGE "Cambia filamento"
#define MSG_INIT_SDCARD "Iniz. SD-Card" #define MSG_INIT_SDCARD "Iniz. SD-Card"
#define MSG_CNG_SDCARD "Cambia SD-Card" #define MSG_CNG_SDCARD "Cambia SD-Card"
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
@ -1268,7 +1286,6 @@
#define MSG_BROWNOUT_RESET " Brown out Reset" #define MSG_BROWNOUT_RESET " Brown out Reset"
#define MSG_WATCHDOG_RESET " Watchdog Reset" #define MSG_WATCHDOG_RESET " Watchdog Reset"
#define MSG_SOFTWARE_RESET " Software Reset" #define MSG_SOFTWARE_RESET " Software Reset"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Autore: " #define MSG_AUTHOR " | Autore: "
#define MSG_CONFIGURATION_VER " Ultimo Aggiornamento: " #define MSG_CONFIGURATION_VER " Ultimo Aggiornamento: "
#define MSG_FREE_MEMORY " Memoria Libera: " #define MSG_FREE_MEMORY " Memoria Libera: "
@ -1334,6 +1351,7 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Qualcosa non va in MenuStructure."
#endif #endif
@ -1341,25 +1359,27 @@
#if LANGUAGE_CHOICE == 8 #if LANGUAGE_CHOICE == 8
// LCD Menu Messages // LCD Menu Messages
#define WELCOME_MSG MACHINE_NAME " Pronta." // Please note these are limited to 17 characters!
#define MSG_SD_INSERTED "Cartao SD inserido"
#define MSG_SD_REMOVED "Cartao SD removido" #define WELCOME_MSG MACHINE_NAME " pronto."
#define MSG_MAIN " Menu Principal \003" #define MSG_SD_INSERTED "Cartao inserido"
#define MSG_SD_REMOVED "Cartao removido"
#define MSG_MAIN " Menu principal \003"
#define MSG_AUTOSTART "Autostart" #define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS " Apagar Motores" #define MSG_DISABLE_STEPPERS " Apagar motores"
#define MSG_AUTO_HOME " Ir para Origen" #define MSG_AUTO_HOME "Ir para origen"
#define MSG_SET_ORIGIN " Estabelecer Origen" #define MSG_SET_ORIGIN "Estabelecer orig."
#define MSG_PREHEAT_PLA " pre-aquecer PLA" #define MSG_PREHEAT_PLA "Pre-aquecer PLA"
#define MSG_PREHEAT_PLA_SETTINGS " pre-aquecer PLA Setting" #define MSG_PREHEAT_PLA_SETTINGS "PLA setting"
#define MSG_PREHEAT_ABS " pre-aquecer ABS" #define MSG_PREHEAT_ABS "Pre-aquecer ABS"
#define MSG_PREHEAT_ABS_SETTINGS " pre-aquecer ABS Setting" #define MSG_PREHEAT_ABS_SETTINGS "ABS setting"
#define MSG_COOLDOWN "Esfriar" #define MSG_COOLDOWN "Esfriar"
#define MSG_SWITCH_PS_ON "Switch Power On" #define MSG_SWITCH_PS_ON "Switch Power On"
#define MSG_SWITCH_PS_OFF "Switch Power Off" #define MSG_SWITCH_PS_OFF "Switch Power Off"
#define MSG_EXTRUDE "Extrudar" #define MSG_EXTRUDE "Extrudar"
#define MSG_RETRACT "Retrair" #define MSG_RETRACT "Retrair"
#define MSG_PREHEAT_PLA " pre-aquecer PLA" #define MSG_PREHEAT_PLA "Pre-aquecer PLA"
#define MSG_PREHEAT_ABS " pre-aquecer ABS" #define MSG_PREHEAT_ABS "Pre-aquecer ABS"
#define MSG_MOVE_AXIS "Mover eixo \x7E" #define MSG_MOVE_AXIS "Mover eixo \x7E"
#define MSG_MOVE_X "Move X" #define MSG_MOVE_X "Move X"
#define MSG_MOVE_Y "Move Y" #define MSG_MOVE_Y "Move Y"
@ -1373,7 +1393,7 @@
#define MSG_NOZZLE1 "\002Nozzle2:" #define MSG_NOZZLE1 "\002Nozzle2:"
#define MSG_NOZZLE2 "\002Nozzle3:" #define MSG_NOZZLE2 "\002Nozzle3:"
#define MSG_BED "\002Base:" #define MSG_BED "\002Base:"
#define MSG_FAN_SPEED " Velocidade Ventoinha:" #define MSG_FAN_SPEED "Velocidade vento."
#define MSG_FLOW "Fluxo:" #define MSG_FLOW "Fluxo:"
#define MSG_CONTROL "Controle \003" #define MSG_CONTROL "Controle \003"
#define MSG_MIN "\002 Min:" #define MSG_MIN "\002 Min:"
@ -1409,7 +1429,7 @@
#define MSG_MOTION "Movimento" #define MSG_MOTION "Movimento"
#define MSG_STORE_EPROM "Guardar memoria" #define MSG_STORE_EPROM "Guardar memoria"
#define MSG_LOAD_EPROM "Carregar memoria" #define MSG_LOAD_EPROM "Carregar memoria"
#define MSG_RESTORE_FAILSAFE " Rest. de emergencia" #define MSG_RESTORE_FAILSAFE "Rest. de emergen."
#define MSG_REFRESH "\004Recarregar" #define MSG_REFRESH "\004Recarregar"
#define MSG_WATCH "Monitorar \003" #define MSG_WATCH "Monitorar \003"
#define MSG_PREPARE "Preparar \x7E" #define MSG_PREPARE "Preparar \x7E"
@ -1417,17 +1437,16 @@
#define MSG_CONTROL_ARROW "Controle \x7E" #define MSG_CONTROL_ARROW "Controle \x7E"
#define MSG_RETRACT_ARROW "Retrair \x7E" #define MSG_RETRACT_ARROW "Retrair \x7E"
#define MSG_TUNE "Tune \x7E" #define MSG_TUNE "Tune \x7E"
#define MSG_PAUSE_PRINT " Pausar Impressao \x7E" #define MSG_PAUSE_PRINT "Pausar impressao"
#define MSG_RESUME_PRINT " Resumir Impressao \x7E" #define MSG_RESUME_PRINT "Resumir impressao"
#define MSG_STOP_PRINT " Parar Impressao \x7E" #define MSG_STOP_PRINT "Parar impressao"
#define MSG_CARD_MENU " Menu cartao SD \x7E" #define MSG_CARD_MENU "Menu cartao SD"
#define MSG_NO_CARD "Sem cartao SD" #define MSG_NO_CARD "Sem cartao SD"
#define MSG_DWELL "Repouso..." #define MSG_DWELL "Repouso..."
#define MSG_USERWAIT "Esperando Ordem..." #define MSG_USERWAIT "Esperando ordem"
#define MSG_RESUMING "Resuming print" #define MSG_RESUMING "Resuming print"
#define MSG_NO_MOVE "Sem movimento." #define MSG_NO_MOVE "Sem movimento"
#define MSG_PART_RELEASE "Lancamento Parcial" #define MSG_KILLED "PARADA DE EMERG."
#define MSG_KILLED "PARADA DE EMERGENCIA. "
#define MSG_STOPPED "PARADA. " #define MSG_STOPPED "PARADA. "
#define MSG_STEPPER_RELEASED "Lancado." #define MSG_STEPPER_RELEASED "Lancado."
#define MSG_CONTROL_RETRACT " Retrair mm:" #define MSG_CONTROL_RETRACT " Retrair mm:"
@ -1436,12 +1455,11 @@
#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_FILAMENTCHANGE "Change filament" #define MSG_FILAMENTCHANGE "Change filament"
#define MSG_INIT_SDCARD "Init. SD-Card" #define MSG_INIT_SDCARD "Init. SD-Card"
#define MSG_CNG_SDCARD "Change SD-Card" #define MSG_CNG_SDCARD "Change SD-Card"
#define MSG_ZPROBE_OUT "Sonda fora da mesa" #define MSG_ZPROBE_OUT "Son. fora da mesa"
#define MSG_POSITION_UNKNOWN "Home X/Y antes de Z" #define MSG_POSITION_UNKNOWN "XY antes de Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y" #define MSG_BABYSTEP_Y "Babystep Y"
@ -1457,7 +1475,6 @@
#define MSG_BROWNOUT_RESET " Reset por voltagem incorreta" #define MSG_BROWNOUT_RESET " Reset por voltagem incorreta"
#define MSG_WATCHDOG_RESET " Reset por Bloqueio" #define MSG_WATCHDOG_RESET " Reset por Bloqueio"
#define MSG_SOFTWARE_RESET " Reset por Software" #define MSG_SOFTWARE_RESET " Reset por Software"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Author: " #define MSG_AUTHOR " | Author: "
#define MSG_CONFIGURATION_VER " Ultima atualizacao: " #define MSG_CONFIGURATION_VER " Ultima atualizacao: "
#define MSG_FREE_MEMORY " memoria Livre: " #define MSG_FREE_MEMORY " memoria Livre: "
@ -1523,6 +1540,7 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Algo esta errado na estrutura do Menu."
#endif #endif
@ -1530,10 +1548,10 @@
#if LANGUAGE_CHOICE == 9 #if LANGUAGE_CHOICE == 9
// Finnish
// LCD Menu Messages // LCD Menu Messages
#define WELCOME_MSG MACHINE_NAME " valmis" // Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " valmis."
#define MSG_SD_INSERTED "Kortti asetettu" #define MSG_SD_INSERTED "Kortti asetettu"
#define MSG_SD_REMOVED "Kortti poistettu" #define MSG_SD_REMOVED "Kortti poistettu"
#define MSG_MAIN "Palaa" #define MSG_MAIN "Palaa"
@ -1542,12 +1560,12 @@
#define MSG_AUTO_HOME "Aja referenssiin" #define MSG_AUTO_HOME "Aja referenssiin"
#define MSG_SET_ORIGIN "Aseta origo" #define MSG_SET_ORIGIN "Aseta origo"
#define MSG_PREHEAT_PLA "Esilammita PLA" #define MSG_PREHEAT_PLA "Esilammita PLA"
#define MSG_PREHEAT_PLA_SETTINGS "Esilammita PLA konf" #define MSG_PREHEAT_PLA_SETTINGS "Esilamm. PLA konf"
#define MSG_PREHEAT_ABS "Esilammita ABS" #define MSG_PREHEAT_ABS "Esilammita ABS"
#define MSG_PREHEAT_ABS_SETTINGS "Esilammita ABS konf" #define MSG_PREHEAT_ABS_SETTINGS "Esilamm. ABS konf"
#define MSG_COOLDOWN "Jaahdyta" #define MSG_COOLDOWN "Jaahdyta"
#define MSG_SWITCH_PS_ON "Switch Power On" #define MSG_SWITCH_PS_ON "Virta paalle"
#define MSG_SWITCH_PS_OFF "Switch Power Off" #define MSG_SWITCH_PS_OFF "Virta pois"
#define MSG_EXTRUDE "Pursota" #define MSG_EXTRUDE "Pursota"
#define MSG_RETRACT "Veda takaisin" #define MSG_RETRACT "Veda takaisin"
#define MSG_MOVE_AXIS "Liikuta akseleita" #define MSG_MOVE_AXIS "Liikuta akseleita"
@ -1610,8 +1628,8 @@
#define MSG_CARD_MENU "Korttivalikko" #define MSG_CARD_MENU "Korttivalikko"
#define MSG_NO_CARD "Ei korttia" #define MSG_NO_CARD "Ei korttia"
#define MSG_DWELL "Nukkumassa..." #define MSG_DWELL "Nukkumassa..."
#define MSG_USERWAIT "Odotetaan valintaa..." #define MSG_USERWAIT "Odotet. valintaa"
#define MSG_RESUMING "Jatketaan tulostusta" #define MSG_RESUMING "Jatke. tulostusta"
#define MSG_NO_MOVE "Ei liiketta." #define MSG_NO_MOVE "Ei liiketta."
#define MSG_KILLED "KILLED. " #define MSG_KILLED "KILLED. "
#define MSG_STOPPED "STOPPED. " #define MSG_STOPPED "STOPPED. "
@ -1624,14 +1642,13 @@
#define MSG_FILAMENTCHANGE "Change filament" #define MSG_FILAMENTCHANGE "Change filament"
#define MSG_INIT_SDCARD "Init. SD-Card" #define MSG_INIT_SDCARD "Init. SD-Card"
#define MSG_CNG_SDCARD "Change SD-Card" #define MSG_CNG_SDCARD "Change SD-Card"
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
#define MSG_BABYSTEP_Y "Babystep Y" #define MSG_BABYSTEP_Y "Babystep Y"
#define MSG_BABYSTEP_Z "Babystep Z" #define MSG_BABYSTEP_Z "Babystep Z"
#define MSG_ENDSTOP_ABORT "Endstop abort" #define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_CONTRAST "Contrast"
// Serial Console Messages // Serial Console Messages
@ -1641,7 +1658,6 @@
#define MSG_BROWNOUT_RESET " Alajannite Reset" #define MSG_BROWNOUT_RESET " Alajannite Reset"
#define MSG_WATCHDOG_RESET " Vahtikoira Reset" #define MSG_WATCHDOG_RESET " Vahtikoira Reset"
#define MSG_SOFTWARE_RESET " Ohjelmisto Reset" #define MSG_SOFTWARE_RESET " Ohjelmisto Reset"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Author: " #define MSG_AUTHOR " | Author: "
#define MSG_CONFIGURATION_VER " Paivitetty viimeksi: " #define MSG_CONFIGURATION_VER " Paivitetty viimeksi: "
#define MSG_FREE_MEMORY " Vapaata muistia: " #define MSG_FREE_MEMORY " Vapaata muistia: "
@ -1708,25 +1724,28 @@
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_ENDSTOP_ABORT "Endstop abort" #define MSG_ENDSTOP_ABORT "Endstop abort"
#define MSG_CONTRAST "Contrast" #define MSG_CONTRAST "Kontrasti"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Virhe valikon rakenteessa"
#endif #endif
#if LANGUAGE_CHOICE == 10 #if LANGUAGE_CHOICE == 10
// LCD Menu Messages // LCD Menu Messages
#define WELCOME_MSG MACHINE_NAME " Parada." // Please note these are limited to 17 characters!
#define MSG_SD_INSERTED "Tarcheta SD Colocada"
#define MSG_SD_REMOVED "Tarcheta SD Retirada" #define WELCOME_MSG MACHINE_NAME " parada."
#define MSG_MAIN "Menu Prencipal" #define MSG_SD_INSERTED "Tarcheta colocada"
#define MSG_SD_REMOVED "Tarcheta retirada"
#define MSG_MAIN "Menu prencipal"
#define MSG_AUTOSTART " Autostart" #define MSG_AUTOSTART " Autostart"
#define MSG_DISABLE_STEPPERS "Amortar Motors" #define MSG_DISABLE_STEPPERS "Amortar motors"
#define MSG_AUTO_HOME "Levar a l'Orichen" // "Levar Eixes a o Zero" #define MSG_AUTO_HOME "Levar a l'orichen"
#define MSG_SET_ORIGIN "Establir Zero" #define MSG_SET_ORIGIN "Establir zero"
#define MSG_PREHEAT_PLA "Precalentar PLA" #define MSG_PREHEAT_PLA "Precalentar PLA"
#define MSG_PREHEAT_PLA_SETTINGS "Achustar temp. PLA" #define MSG_PREHEAT_PLA_SETTINGS "Achustar tem. PLA"
#define MSG_PREHEAT_ABS "Precalentar ABS" #define MSG_PREHEAT_ABS "Precalentar ABS"
#define MSG_PREHEAT_ABS_SETTINGS "Achustar temp. ABS" #define MSG_PREHEAT_ABS_SETTINGS "Achustar tem. ABS"
#define MSG_COOLDOWN "Enfriar" #define MSG_COOLDOWN "Enfriar"
#define MSG_SWITCH_PS_ON "Enchegar Fuent" #define MSG_SWITCH_PS_ON "Enchegar Fuent"
#define MSG_SWITCH_PS_OFF "Desenchegar Fuent" #define MSG_SWITCH_PS_OFF "Desenchegar Fuent"
@ -1780,21 +1799,21 @@
#define MSG_MOTION "Movimiento" #define MSG_MOTION "Movimiento"
#define MSG_STORE_EPROM "Alzar Memoria" #define MSG_STORE_EPROM "Alzar Memoria"
#define MSG_LOAD_EPROM "Cargar Memoria" #define MSG_LOAD_EPROM "Cargar Memoria"
#define MSG_RESTORE_FAILSAFE "Rest. d'emerchencia" #define MSG_RESTORE_FAILSAFE "Rest. d'emerchen."
#define MSG_REFRESH "Tornar a cargar" #define MSG_REFRESH "Tornar a cargar"
#define MSG_WATCH "Monitorizar" #define MSG_WATCH "Monitorizar"
#define MSG_PREPARE "Preparar" #define MSG_PREPARE "Preparar"
#define MSG_TUNE "Achustar" #define MSG_TUNE "Achustar"
#define MSG_PAUSE_PRINT "Pausar Impresion" #define MSG_PAUSE_PRINT "Pausar impresion"
#define MSG_RESUME_PRINT "Continar Impresion" #define MSG_RESUME_PRINT "Contin. impresion"
#define MSG_STOP_PRINT "Detener Impresion" #define MSG_STOP_PRINT "Detener Impresion"
#define MSG_CARD_MENU "Menu de SD" #define MSG_CARD_MENU "Menu de SD"
#define MSG_NO_CARD "No i hai Tarcheta SD" #define MSG_NO_CARD "No i hai tarcheta"
#define MSG_DWELL "Reposo..." #define MSG_DWELL "Reposo..."
#define MSG_USERWAIT "Asperando Ordines..." #define MSG_USERWAIT "Asperan. ordines"
#define MSG_RESUMING "Continando Impresion" #define MSG_RESUMING "Contin. impresion"
#define MSG_NO_MOVE "Sin movimiento" #define MSG_NO_MOVE "Sin movimiento"
#define MSG_KILLED "ATURADA D'EMERCHENCIA. " #define MSG_KILLED "ATURADA D'EMERCH."
#define MSG_STOPPED "ATURADA." #define MSG_STOPPED "ATURADA."
#define MSG_CONTROL_RETRACT "Retraer mm" #define MSG_CONTROL_RETRACT "Retraer mm"
#define MSG_CONTROL_RETRACTF "Retraer F" #define MSG_CONTROL_RETRACTF "Retraer F"
@ -1803,8 +1822,8 @@
#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 "Cambear" #define MSG_FILAMENTCHANGE "Cambear"
#define MSG_INIT_SDCARD "Encetando. Tarcheta-SD" #define MSG_INIT_SDCARD "Encetan. tarcheta"
#define MSG_CNG_SDCARD "Cambiar Tarcheta-SD" #define MSG_CNG_SDCARD "Cambiar tarcheta"
#define MSG_RECTRACT_WIDE "Retraer" #define MSG_RECTRACT_WIDE "Retraer"
#define MSG_TEMPERATURE_WIDE "Temperatura" #define MSG_TEMPERATURE_WIDE "Temperatura"
#define MSG_TEMPERATURE_RTN "Temperatura" #define MSG_TEMPERATURE_RTN "Temperatura"
@ -1813,9 +1832,8 @@
#define MSG_PREPARE_ALT "Preparar" #define MSG_PREPARE_ALT "Preparar"
#define MSG_CONTROL_ARROW "Control" #define MSG_CONTROL_ARROW "Control"
#define MSG_RETRACT_ARROW "Retraer" #define MSG_RETRACT_ARROW "Retraer"
#define MSG_PART_RELEASE "Desacople Parcial"
#define MSG_STEPPER_RELEASED "Desacoplada." #define MSG_STEPPER_RELEASED "Desacoplada."
#define MSG_ZPROBE_OUT "ZProbe Outside Bed" #define MSG_ZPROBE_OUT "Z probe out. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y before Z" #define MSG_POSITION_UNKNOWN "Home X/Y before Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset" #define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystep X" #define MSG_BABYSTEP_X "Babystep X"
@ -1832,7 +1850,6 @@
#define MSG_BROWNOUT_RESET " Reset por Voltaje Incorrecto" #define MSG_BROWNOUT_RESET " Reset por Voltaje Incorrecto"
#define MSG_WATCHDOG_RESET " Reset por Bloqueo" #define MSG_WATCHDOG_RESET " Reset por Bloqueo"
#define MSG_SOFTWARE_RESET " Reset por Software" #define MSG_SOFTWARE_RESET " Reset por Software"
#define MSG_MARLIN "Marlin "
#define MSG_AUTHOR " | Autor: " #define MSG_AUTHOR " | Autor: "
#define MSG_CONFIGURATION_VER " Zaguer esvielle: " #define MSG_CONFIGURATION_VER " Zaguer esvielle: "
#define MSG_FREE_MEMORY " Memoria libre: " #define MSG_FREE_MEMORY " Memoria libre: "
@ -1897,6 +1914,188 @@
#define MSG_BABYSTEPPING_X "Babystepping X" #define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y" #define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z" #define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
#endif
#if LANGUAGE_CHOICE == 11 //Dutch
// LCD Menu Messages
// Please note these are limited to 17 characters!
#define WELCOME_MSG MACHINE_NAME " gereed."
#define MSG_SD_INSERTED "Kaart ingestoken"
#define MSG_SD_REMOVED "Kaart verwijderd"
#define MSG_MAIN "Main"
#define MSG_AUTOSTART "Autostart"
#define MSG_DISABLE_STEPPERS "Motoren uit"
#define MSG_AUTO_HOME "Auto home"
#define MSG_SET_ORIGIN "Nulpunt instellen"
#define MSG_PREHEAT_PLA "PLA voorverwarmen"
#define MSG_PREHEAT_PLA_SETTINGS "PLA verw. conf"
#define MSG_PREHEAT_ABS "ABS voorverwarmen"
#define MSG_PREHEAT_ABS_SETTINGS "ABS verw. conf"
#define MSG_COOLDOWN "Afkoelen"
#define MSG_SWITCH_PS_ON "Stroom aan"
#define MSG_SWITCH_PS_OFF "Stroom uit"
#define MSG_EXTRUDE "Extrude"
#define MSG_RETRACT "Retract"
#define MSG_MOVE_AXIS "As verplaatsen"
#define MSG_MOVE_X "Verplaats X"
#define MSG_MOVE_Y "Verplaats Y"
#define MSG_MOVE_Z "Verplaats Z"
#define MSG_MOVE_E "Extruder"
#define MSG_MOVE_01MM "Verplaats 0.1mm"
#define MSG_MOVE_1MM "Verplaats 1mm"
#define MSG_MOVE_10MM "Verplaats 10mm"
#define MSG_SPEED "Snelheid"
#define MSG_NOZZLE "Nozzle"
#define MSG_NOZZLE1 "Nozzle2"
#define MSG_NOZZLE2 "Nozzle3"
#define MSG_BED "Bed"
#define MSG_FAN_SPEED "Fan snelheid"
#define MSG_FLOW "Flow"
#define MSG_CONTROL "Control"
#define MSG_MIN " \002 Min"
#define MSG_MAX " \002 Max"
#define MSG_FACTOR " \002 Fact"
#define MSG_AUTOTEMP "Autotemp"
#define MSG_ON "Aan "
#define MSG_OFF "Uit"
#define MSG_PID_P "PID-P"
#define MSG_PID_I "PID-I"
#define MSG_PID_D "PID-D"
#define MSG_PID_C "PID-C"
#define MSG_ACC "Versn"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
#define MSG_VE_JERK "Ve-jerk"
#define MSG_VMAX "Vmax "
#define MSG_X "x"
#define MSG_Y "y"
#define MSG_Z "z"
#define MSG_E "e"
#define MSG_VMIN "Vmin"
#define MSG_VTRAV_MIN "VTrav min"
#define MSG_AMAX "Amax "
#define MSG_A_RETRACT "A-retract"
#define MSG_XSTEPS "Xsteps/mm"
#define MSG_YSTEPS "Ysteps/mm"
#define MSG_ZSTEPS "Zsteps/mm"
#define MSG_ESTEPS "Esteps/mm"
#define MSG_RECTRACT "Terugtrekken"
#define MSG_TEMPERATURE "Temperatuur"
#define MSG_MOTION "Beweging"
#define MSG_CONTRAST "LCD contrast"
#define MSG_STORE_EPROM "Geheugen opslaan"
#define MSG_LOAD_EPROM "Geheugen laden"
#define MSG_RESTORE_FAILSAFE "Noodstop reset"
#define MSG_REFRESH "Ververs"
#define MSG_WATCH "Info scherm"
#define MSG_PREPARE "Voorbereiden"
#define MSG_TUNE "Afstellen"
#define MSG_PAUSE_PRINT "Print pauzeren"
#define MSG_RESUME_PRINT "Print hervatten"
#define MSG_STOP_PRINT "Print stoppen"
#define MSG_CARD_MENU "Print van SD"
#define MSG_NO_CARD "Geen SD kaart"
#define MSG_DWELL "Slapen..."
#define MSG_USERWAIT "Wachten..."
#define MSG_RESUMING "Print hervatten"
#define MSG_NO_MOVE "Geen beweging."
#define MSG_KILLED "AFGEBROKEN. "
#define MSG_STOPPED "GESTOPT. "
#define MSG_CONTROL_RETRACT "Retract mm"
#define MSG_CONTROL_RETRACTF "Retract F"
#define MSG_CONTROL_RETRACT_ZLIFT "Hop mm"
#define MSG_CONTROL_RETRACT_RECOVER "UnRet +mm"
#define MSG_CONTROL_RETRACT_RECOVERF "UnRet F"
#define MSG_AUTORETRACT "AutoRetr."
#define MSG_FILAMENTCHANGE "Verv. Filament"
#define MSG_INIT_SDCARD "Init. SD kaart"
#define MSG_CNG_SDCARD "Verv. SD card"
#define MSG_ZPROBE_OUT "Z probe uit. bed"
#define MSG_POSITION_UNKNOWN "Home X/Y voor Z"
#define MSG_ZPROBE_ZOFFSET "Z Offset"
#define MSG_BABYSTEP_X "Babystap X"
#define MSG_BABYSTEP_Y "Babystap Y"
#define MSG_BABYSTEP_Z "Babystap Z"
#define MSG_ENDSTOP_ABORT "Endstop afbr."
// Serial Console Messages
#define MSG_Enqueing "enqueing \""
#define MSG_POWERUP "Opstarten"
#define MSG_EXTERNAL_RESET " Externe Reset"
#define MSG_BROWNOUT_RESET " Lage voedingsspanning Reset"
#define MSG_WATCHDOG_RESET " Watchdog Reset"
#define MSG_SOFTWARE_RESET " Software Reset"
#define MSG_AUTHOR " | Auteur: "
#define MSG_CONFIGURATION_VER " Laatst bijgewerkt: "
#define MSG_FREE_MEMORY " Vrij Geheugen: "
#define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
#define MSG_OK "ok"
#define MSG_FILE_SAVED "Bestand opslaan voltooid."
#define MSG_ERR_LINE_NO "Regelnummer is niet het laatste regelnummer+1, Laatste regel: "
#define MSG_ERR_CHECKSUM_MISMATCH "Checksum fout, Laatste regel: "
#define MSG_ERR_NO_CHECKSUM "Regel zonder checksum, Laatste regel: "
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM "Geen regelnummer met checksum, Laatste regel: "
#define MSG_FILE_PRINTED "Bestand afdrukken klaar"
#define MSG_BEGIN_FILE_LIST "Begin bestandslijst"
#define MSG_END_FILE_LIST "Einde bestandslijst"
#define MSG_M104_INVALID_EXTRUDER "M104 Ongeldige extruder "
#define MSG_M105_INVALID_EXTRUDER "M105 Ongeldige extruder "
#define MSG_M200_INVALID_EXTRUDER "M200 Ongeldige extruder "
#define MSG_M218_INVALID_EXTRUDER "M218 Ongeldige extruder "
#define MSG_ERR_NO_THERMISTORS "Geen thermistors - geen temperatuur"
#define MSG_M109_INVALID_EXTRUDER "M109 Ongeldige extruder "
#define MSG_HEATING "Opwarmen..."
#define MSG_HEATING_COMPLETE "Opwarmen klaar."
#define MSG_BED_HEATING "Bed opwarmen."
#define MSG_BED_DONE "Bed klaar."
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1; Sprinter/grbl mashup voor gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
#define MSG_COUNT_X " Aantal X: "
#define MSG_ERR_KILLED "Printer stopgezet. kill() aangeroepen!"
#define MSG_ERR_STOPPED "Printer gestopt vanwege fouten. Los de fout op en gebruik M999 om opnieuw te starten. (Temperatuur is gereset, stel deze opnieuw in na herstart)"
#define MSG_RESEND "Opnieuw sturen: "
#define MSG_UNKNOWN_COMMAND "Onbekend commando: \""
#define MSG_ACTIVE_EXTRUDER "Actieve Extruder: "
#define MSG_INVALID_EXTRUDER "Ongeldige extruder"
#define MSG_X_MIN "x_min: "
#define MSG_X_MAX "x_max: "
#define MSG_Y_MIN "y_min: "
#define MSG_Y_MAX "y_max: "
#define MSG_Z_MIN "z_min: "
#define MSG_Z_MAX "z_max: "
#define MSG_M119_REPORT "Eindstop statusrapportage:"
#define MSG_ENDSTOP_HIT "GERAAKT"
#define MSG_ENDSTOP_OPEN "open"
#define MSG_HOTEND_OFFSET "Hotend afwijking:"
#define MSG_SD_CANT_OPEN_SUBDIR "Kan subdirectory niet openen"
#define MSG_SD_INIT_FAIL "SD initialiseren mislukt"
#define MSG_SD_VOL_INIT_FAIL "volume.init mislukt"
#define MSG_SD_OPENROOT_FAIL "openRoot mislukt"
#define MSG_SD_CARD_OK "SD kaart ok"
#define MSG_SD_WORKDIR_FAIL "workDir openen mislukt"
#define MSG_SD_OPEN_FILE_FAIL "Openen mislukt, bestand: "
#define MSG_SD_FILE_OPENED "Bestand geopend: "
#define MSG_SD_SIZE " Grootte: "
#define MSG_SD_FILE_SELECTED "Bestanden geselecteerd:"
#define MSG_SD_WRITE_TO_FILE "Schrijven naar bestand: "
#define MSG_SD_PRINTING_BYTE "SD printen byte: "
#define MSG_SD_NOT_PRINTING "Niet SD printen"
#define MSG_SD_ERR_WRITE_TO_FILE "Fout tijdens het schrijven naar bestand:"
#define MSG_SD_CANT_ENTER_SUBDIR "Kan subdirectory niet in: "
#define MSG_STEPPER_TOO_HIGH "stapsnelheid te hoog:"
#define MSG_ENDSTOPS_HIT "endstops geraakt: "
#define MSG_ERR_COLD_EXTRUDE_STOP " Koude extrusie voorkomen"
#define MSG_ERR_LONG_EXTRUDE_STOP " te lange extrusie voorkomen"
#define MSG_BABYSTEPPING_X "Babystepping X"
#define MSG_BABYSTEPPING_Y "Babystepping Y"
#define MSG_BABYSTEPPING_Z "Babystepping Z"
#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Fout in menustructuur"
#endif #endif

View File

@ -1381,7 +1381,7 @@
#define SDSS 53 #define SDSS 53
#define LED_PIN 8 #define LED_PIN 8
#define FAN_PIN 7 #define FAN_PIN 7
#define PS_ON_PIN 12 #define PS_ON_PIN -1
#define KILL_PIN -1 #define KILL_PIN -1
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing. #define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
#define SAFETY_TRIGGERED_PIN 28 //PIN to detect the safety circuit has triggered #define SAFETY_TRIGGERED_PIN 28 //PIN to detect the safety circuit has triggered
@ -1781,8 +1781,8 @@
#define Z_DIR_PIN 28 #define Z_DIR_PIN 28
#define Z_STOP_PIN 30 #define Z_STOP_PIN 30
#define E_STEP_PIN 17 #define E0_STEP_PIN 17
#define E_DIR_PIN 21 #define E0_DIR_PIN 21
#define LED_PIN -1 #define LED_PIN -1
@ -1793,15 +1793,16 @@
#define HEATER_0_PIN 12 // (extruder) #define HEATER_0_PIN 12 // (extruder)
#define HEATER_1_PIN 16 // (bed) #define HEATER_BED_PIN 16 // (bed)
#define X_ENABLE_PIN 19 #define X_ENABLE_PIN 19
#define Y_ENABLE_PIN 24 #define Y_ENABLE_PIN 24
#define Z_ENABLE_PIN 29 #define Z_ENABLE_PIN 29
#define E_ENABLE_PIN 13 #define E0_ENABLE_PIN 13
#define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder) #define TEMP_0_PIN 0 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder)
#define TEMP_1_PIN 5 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed) #define TEMP_1_PIN -1
#define TEMP_2_PIN -1 #define TEMP_2_PIN -1
#define TEMP_BED_PIN 5 // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
#define SDPOWER -1 #define SDPOWER -1
#define SDSS 4 #define SDSS 4
#define HEATER_2_PIN -1 #define HEATER_2_PIN -1

View File

@ -1,11 +1,9 @@
#include "qr_solve.h" #include "qr_solve.h"
#ifdef ACCURATE_BED_LEVELING #ifdef AUTO_BED_LEVELING_GRID
#include <stdlib.h> #include <stdlib.h>
#include <math.h> #include <math.h>
#include <time.h>
//# include "r8lib.h" //# include "r8lib.h"
@ -1173,7 +1171,7 @@ void dqrlss ( double a[], int lda, int m, int n, int kr, double b[], double x[],
Discussion: Discussion:
DQRLSS must be preceeded by a call to DQRANK. DQRLSS must be preceded by a call to DQRANK.
The system is to be solved is The system is to be solved is
A * X = B A * X = B
@ -1225,7 +1223,7 @@ void dqrlss ( double a[], int lda, int m, int n, int kr, double b[], double x[],
linear system. linear system.
Output, double RSD[M], the residual, B - A*X. RSD may Output, double RSD[M], the residual, B - A*X. RSD may
overwite B. overwrite B.
Input, int JPVT[N], the pivot information from DQRANK. Input, int JPVT[N], the pivot information from DQRANK.
Columns JPVT[0], ..., JPVT[KR-1] of the original matrix are linearly Columns JPVT[0], ..., JPVT[KR-1] of the original matrix are linearly
@ -1314,7 +1312,7 @@ int dqrsl ( double a[], int lda, int n, int k, double qraux[], double y[],
can be replaced by dummy variables in the calling program. can be replaced by dummy variables in the calling program.
To save storage, the user may in some cases use the same To save storage, the user may in some cases use the same
array for different parameters in the calling sequence. A array for different parameters in the calling sequence. A
frequently occuring example is when one wishes to compute frequently occurring example is when one wishes to compute
any of B, RSD, or AB and does not need Y or QTY. In this any of B, RSD, or AB and does not need Y or QTY. In this
case one may identify Y, QTY, and one of B, RSD, or AB, while case one may identify Y, QTY, and one of B, RSD, or AB, while
providing separate arrays for anything else that is to be providing separate arrays for anything else that is to be

View File

@ -1,6 +1,6 @@
#include "Configuration.h" #include "Configuration.h"
#ifdef ACCURATE_BED_LEVELING #ifdef AUTO_BED_LEVELING_GRID
void daxpy ( int n, double da, double dx[], int incx, double dy[], int incy ); void daxpy ( int n, double da, double dx[], int incx, double dy[], int incy );
double ddot ( int n, double dx[], int incx, double dy[], int incy ); double ddot ( int n, double dx[], int incx, double dy[], int incy );

View File

@ -71,8 +71,8 @@ float st_get_position_mm(uint8_t axis);
void st_wake_up(); void st_wake_up();
void checkHitEndstops(); //call from somwhere to create an serial error message with the locations the endstops where hit, in case they were triggered void checkHitEndstops(); //call from somewhere to create an serial error message with the locations the endstops where hit, in case they were triggered
void endstops_hit_on_purpose(); //avoid creation of the message, i.e. after homeing and before a routine call of checkHitEndstops(); void endstops_hit_on_purpose(); //avoid creation of the message, i.e. after homing and before a routine call of checkHitEndstops();
void enable_endstops(bool check); // Enable/disable endstop checking void enable_endstops(bool check); // Enable/disable endstop checking

View File

@ -250,7 +250,7 @@ void PID_autotune(float temp, int extruder, int ncycles)
Kp = 0.6*Ku; Kp = 0.6*Ku;
Ki = 2*Kp/Tu; Ki = 2*Kp/Tu;
Kd = Kp*Tu/8; Kd = Kp*Tu/8;
SERIAL_PROTOCOLLNPGM(" Clasic PID "); SERIAL_PROTOCOLLNPGM(" Classic PID ");
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(Kp); SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(Kp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(Ki); SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(Ki);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(Kd); SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(Kd);
@ -306,7 +306,7 @@ void PID_autotune(float temp, int extruder, int ncycles)
return; return;
} }
if(cycles > ncycles) { if(cycles > ncycles) {
SERIAL_PROTOCOLLNPGM("PID Autotune finished! Put the Kp, Ki and Kd constants into Configuration.h"); SERIAL_PROTOCOLLNPGM("PID Autotune finished! Put the last Kp, Ki and Kd constants from above into Configuration.h");
return; return;
} }
lcd_update(); lcd_update();
@ -449,7 +449,8 @@ void manage_heater()
pid_output = constrain(target_temperature[e], 0, PID_MAX); pid_output = constrain(target_temperature[e], 0, PID_MAX);
#endif //PID_OPENLOOP #endif //PID_OPENLOOP
#ifdef PID_DEBUG #ifdef PID_DEBUG
SERIAL_ECHO_START(" PIDDEBUG "); SERIAL_ECHO_START;
SERIAL_ECHO(" PID_DEBUG ");
SERIAL_ECHO(e); SERIAL_ECHO(e);
SERIAL_ECHO(": Input "); SERIAL_ECHO(": Input ");
SERIAL_ECHO(pid_input); SERIAL_ECHO(pid_input);

View File

@ -28,7 +28,7 @@
#endif #endif
// public functions // public functions
void tp_init(); //initialise the heating void tp_init(); //initialize the heating
void manage_heater(); //it is critical that this is called periodically. void manage_heater(); //it is critical that this is called periodically.
// low level conversion routines // low level conversion routines

View File

@ -857,6 +857,70 @@ const short temptable_60[][2] PROGMEM = {
}; };
#endif #endif
// Pt1000 and Pt100 handling
//
// Rt=R0*(1+a*T+b*T*T) [for T>0]
// a=3.9083E-3, b=-5.775E-7
#define PtA 3.9083E-3
#define PtB -5.775E-7
#define PtRt(T,R0) ((R0)*(1.0+(PtA)*(T)+(PtB)*(T)*(T)))
#define PtAdVal(T,R0,Rup) (short)(1024/(Rup/PtRt(T,R0)+1))
#define PtLine(T,R0,Rup) { PtAdVal(T,R0,Rup)*OVERSAMPLENR, T },
#if (THERMISTORHEATER_0 == 110) || (THERMISTORHEATER_1 == 110) || (THERMISTORHEATER_2 == 110) || (THERMISTORBED == 110) // Pt100 with 1k0 pullup
const short temptable_110[][2] PROGMEM = {
// only few values are needed as the curve is very flat
PtLine(0,100,1000)
PtLine(50,100,1000)
PtLine(100,100,1000)
PtLine(150,100,1000)
PtLine(200,100,1000)
PtLine(250,100,1000)
PtLine(300,100,1000)
};
#endif
#if (THERMISTORHEATER_0 == 147) || (THERMISTORHEATER_1 == 147) || (THERMISTORHEATER_2 == 147) || (THERMISTORBED == 147) // Pt100 with 4k7 pullup
const short temptable_147[][2] PROGMEM = {
// only few values are needed as the curve is very flat
PtLine(0,100,4700)
PtLine(50,100,4700)
PtLine(100,100,4700)
PtLine(150,100,4700)
PtLine(200,100,4700)
PtLine(250,100,4700)
PtLine(300,100,4700)
};
#endif
#if (THERMISTORHEATER_0 == 1010) || (THERMISTORHEATER_1 == 1010) || (THERMISTORHEATER_2 == 1010) || (THERMISTORBED == 1010) // Pt1000 with 1k0 pullup
const short temptable_1010[][2] PROGMEM = {
PtLine(0,1000,1000)
PtLine(25,1000,1000)
PtLine(50,1000,1000)
PtLine(75,1000,1000)
PtLine(100,1000,1000)
PtLine(125,1000,1000)
PtLine(150,1000,1000)
PtLine(175,1000,1000)
PtLine(200,1000,1000)
PtLine(225,1000,1000)
PtLine(250,1000,1000)
PtLine(275,1000,1000)
PtLine(300,1000,1000)
};
#endif
#if (THERMISTORHEATER_0 == 1047) || (THERMISTORHEATER_1 == 1047) || (THERMISTORHEATER_2 == 1047) || (THERMISTORBED == 1047) // Pt1000 with 4k7 pullup
const short temptable_1047[][2] PROGMEM = {
// only few values are needed as the curve is very flat
PtLine(0,1000,4700)
PtLine(50,1000,4700)
PtLine(100,1000,4700)
PtLine(150,1000,4700)
PtLine(200,1000,4700)
PtLine(250,1000,4700)
PtLine(300,1000,4700)
};
#endif
#define _TT_NAME(_N) temptable_ ## _N #define _TT_NAME(_N) temptable_ ## _N
#define TT_NAME(_N) _TT_NAME(_N) #define TT_NAME(_N) _TT_NAME(_N)

View File

@ -38,7 +38,7 @@ char lcd_status_message[LCD_WIDTH+1] = WELCOME_MSG;
#include "ultralcd_implementation_hitachi_HD44780.h" #include "ultralcd_implementation_hitachi_HD44780.h"
#endif #endif
/** forward declerations **/ /** forward declarations **/
void copy_and_scalePID_i(); void copy_and_scalePID_i();
void copy_and_scalePID_d(); void copy_and_scalePID_d();
@ -62,7 +62,7 @@ static void lcd_set_contrast();
static void lcd_control_retract_menu(); static void lcd_control_retract_menu();
static void lcd_sdcard_menu(); static void lcd_sdcard_menu();
static void lcd_quick_feedback();//Cause an LCD refresh, and give the user visual or audiable feedback that something has happend static void lcd_quick_feedback();//Cause an LCD refresh, and give the user visual or audible feedback that something has happened
/* Different types of actions that can be used in menu items. */ /* Different types of actions that can be used in menu items. */
static void menu_action_back(menuFunc_t data); static void menu_action_back(menuFunc_t data);
@ -173,10 +173,10 @@ void* editValue;
int32_t minEditValue, maxEditValue; int32_t minEditValue, maxEditValue;
menuFunc_t callbackFunc; menuFunc_t callbackFunc;
// placeholders for Ki and Kd edits // place-holders for Ki and Kd edits
float raw_Ki, raw_Kd; float raw_Ki, raw_Kd;
/* Main status screen. It's up to the implementation specific part to show what is needed. As this is very display dependend */ /* Main status screen. It's up to the implementation specific part to show what is needed. As this is very display dependent */
static void lcd_status_screen() static void lcd_status_screen()
{ {
if (lcd_status_update_delay) if (lcd_status_update_delay)
@ -196,6 +196,7 @@ static void lcd_status_screen()
lcd_quick_feedback(); lcd_quick_feedback();
} }
#ifdef ULTIPANEL_FEEDMULTIPLY
// 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))
@ -219,6 +220,7 @@ static void lcd_status_screen()
feedmultiply += int(encoderPosition); feedmultiply += int(encoderPosition);
encoderPosition = 0; encoderPosition = 0;
} }
#endif//ULTIPANEL_FEEDMULTIPLY
if (feedmultiply < 10) if (feedmultiply < 10)
feedmultiply = 10; feedmultiply = 10;
@ -460,6 +462,7 @@ static void lcd_move_x()
{ {
if (encoderPosition != 0) if (encoderPosition != 0)
{ {
refresh_cmd_timeout();
current_position[X_AXIS] += float((int)encoderPosition) * move_menu_scale; current_position[X_AXIS] += float((int)encoderPosition) * move_menu_scale;
if (min_software_endstops && 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;
@ -489,6 +492,7 @@ static void lcd_move_y()
{ {
if (encoderPosition != 0) if (encoderPosition != 0)
{ {
refresh_cmd_timeout();
current_position[Y_AXIS] += float((int)encoderPosition) * move_menu_scale; current_position[Y_AXIS] += float((int)encoderPosition) * move_menu_scale;
if (min_software_endstops && 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;
@ -518,6 +522,7 @@ static void lcd_move_z()
{ {
if (encoderPosition != 0) if (encoderPosition != 0)
{ {
refresh_cmd_timeout();
current_position[Z_AXIS] += float((int)encoderPosition) * move_menu_scale; current_position[Z_AXIS] += float((int)encoderPosition) * move_menu_scale;
if (min_software_endstops && 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;
@ -706,7 +711,9 @@ static void lcd_control_motion_menu()
{ {
START_MENU(); START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu); MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
#ifdef ENABLE_AUTO_BED_LEVELING
MENU_ITEM_EDIT(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, 0.5, 50); MENU_ITEM_EDIT(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, 0.5, 50);
#endif
MENU_ITEM_EDIT(float5, MSG_ACC, &acceleration, 500, 99000); MENU_ITEM_EDIT(float5, MSG_ACC, &acceleration, 500, 99000);
MENU_ITEM_EDIT(float3, MSG_VXY_JERK, &max_xy_jerk, 1, 990); MENU_ITEM_EDIT(float3, MSG_VXY_JERK, &max_xy_jerk, 1, 990);
MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &max_z_jerk, 0.1, 990); MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &max_z_jerk, 0.1, 990);
@ -1050,7 +1057,7 @@ void lcd_update()
{ {
lcdDrawUpdate = 2; lcdDrawUpdate = 2;
lcd_oldcardstatus = IS_SD_INSERTED; lcd_oldcardstatus = IS_SD_INSERTED;
lcd_implementation_init(); // to maybe revive the lcd if static electricty killed it. lcd_implementation_init(); // to maybe revive the LCD if static electricity killed it.
if(lcd_oldcardstatus) if(lcd_oldcardstatus)
{ {
@ -1465,7 +1472,7 @@ char *ftostr52(const float &x)
} }
// Callback for after editing PID i value // Callback for after editing PID i value
// 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 #ifdef PIDTEMP
@ -1475,7 +1482,7 @@ void copy_and_scalePID_i()
} }
// 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 #ifdef PIDTEMP

View File

@ -17,7 +17,7 @@
void lcd_setcontrast(uint8_t value); void lcd_setcontrast(uint8_t value);
#endif #endif
static unsigned char blink = 0; // Variable for visualisation of fan rotation in GLCD static unsigned char blink = 0; // Variable for visualization of fan rotation in GLCD
#define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x)) #define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x))
#define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x)) #define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x))
@ -72,7 +72,7 @@
#define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_MIDDLE) #define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons_reprapworld_keypad&EN_REPRAPWORLD_KEYPAD_MIDDLE)
#endif //REPRAPWORLD_KEYPAD #endif //REPRAPWORLD_KEYPAD
#else #else
//atomatic, do not change //atomic, 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)
@ -85,7 +85,7 @@
#define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST)) #define LCD_CLICKED ((buttons&B_MI)||(buttons&B_ST))
#endif//NEWPANEL #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() {}
FORCE_INLINE void lcd_setstatus(const char* message) {} FORCE_INLINE void lcd_setstatus(const char* message) {}

View File

@ -2,8 +2,8 @@
#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 Russian language, a slightly different LCD implementation is used to handle UTF8 characters.
**/ **/
#ifndef REPRAPWORLD_KEYPAD #ifndef REPRAPWORLD_KEYPAD
@ -20,7 +20,7 @@ extern volatile uint16_t buttons; //an extended version of the last checked but
// 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
@ -718,6 +718,7 @@ static void lcd_implementation_quick_feedback()
#endif #endif
#elif defined(BEEPER) && BEEPER > -1 #elif defined(BEEPER) && BEEPER > -1
SET_OUTPUT(BEEPER); SET_OUTPUT(BEEPER);
#if !defined(LCD_FEEDBACK_FREQUENCY_HZ) || !defined(LCD_FEEDBACK_FREQUENCY_DURATION_MS)
for(int8_t i=0;i<10;i++) for(int8_t i=0;i<10;i++)
{ {
WRITE(BEEPER,HIGH); WRITE(BEEPER,HIGH);
@ -725,6 +726,15 @@ static void lcd_implementation_quick_feedback()
WRITE(BEEPER,LOW); WRITE(BEEPER,LOW);
delayMicroseconds(100); delayMicroseconds(100);
} }
#else
for(int8_t i=0;i<(LCD_FEEDBACK_FREQUENCY_DURATION_MS / (1000 / LCD_FEEDBACK_FREQUENCY_HZ));i++)
{
WRITE(BEEPER,HIGH);
delayMicroseconds(1000000 / LCD_FEEDBACK_FREQUENCY_HZ / 2);
WRITE(BEEPER,LOW);
delayMicroseconds(1000000 / LCD_FEEDBACK_FREQUENCY_HZ / 2);
}
#endif
#endif #endif
} }

View File

@ -12,8 +12,8 @@
#define ST7920_DAT_PIN LCD_PINS_ENABLE #define ST7920_DAT_PIN LCD_PINS_ENABLE
#define ST7920_CS_PIN LCD_PINS_RS #define ST7920_CS_PIN LCD_PINS_RS
//#define PAGE_HEIGHT 8 //128 byte frambuffer //#define PAGE_HEIGHT 8 //128 byte framebuffer
//#define PAGE_HEIGHT 16 //256 byte frambuffer //#define PAGE_HEIGHT 16 //256 byte framebuffer
#define PAGE_HEIGHT 32 //512 byte framebuffer #define PAGE_HEIGHT 32 //512 byte framebuffer
#define WIDTH 128 #define WIDTH 128
@ -59,8 +59,8 @@ uint8_t u8g_dev_rrd_st7920_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, vo
ST7920_SET_CMD(); ST7920_SET_CMD();
ST7920_WRITE_BYTE(0x08); //display off, cursor+blink off ST7920_WRITE_BYTE(0x08); //display off, cursor+blink off
ST7920_WRITE_BYTE(0x01); //clear CGRAM ram ST7920_WRITE_BYTE(0x01); //clear CGRAM ram
u8g_Delay(10); //delay for cgram clear u8g_Delay(10); //delay for CGRAM clear
ST7920_WRITE_BYTE(0x3E); //extended mode + gdram active ST7920_WRITE_BYTE(0x3E); //extended mode + GDRAM active
for(y=0;y<HEIGHT/2;y++) //clear GDRAM for(y=0;y<HEIGHT/2;y++) //clear GDRAM
{ {
ST7920_WRITE_BYTE(0x80|y); //set y ST7920_WRITE_BYTE(0x80|y); //set y

View File

@ -22,19 +22,9 @@
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
#include "vector_3.h" #include "vector_3.h"
vector_3::vector_3() vector_3::vector_3() : x(0), y(0), z(0) { }
{
this->x = 0;
this->y = 0;
this->z = 0;
}
vector_3::vector_3(float x, float y, float z) vector_3::vector_3(float x_, float y_, float z_) : x(x_), y(y_), z(z_) { }
{
this->x = x;
this->y = y;
this->z = z;
}
vector_3 vector_3::cross(vector_3 left, vector_3 right) vector_3 vector_3::cross(vector_3 left, vector_3 right)
{ {

View File

@ -4,9 +4,9 @@
#include "Marlin.h" #include "Marlin.h"
#ifdef USE_WATCHDOG #ifdef USE_WATCHDOG
// intialise watch dog with a 1 sec interrupt time // initialize watch dog with a 1 sec interrupt time
void watchdog_init(); void watchdog_init();
// pad the dog/reset watchdog. MUST be called at least every second after the first watchdog_init or avr will go into emergency procedures.. // pad the dog/reset watchdog. MUST be called at least every second after the first watchdog_init or AVR will go into emergency procedures..
void watchdog_reset(); void watchdog_reset();
#else #else
//If we do not have a watchdog, then we can have empty functions which are optimized away. //If we do not have a watchdog, then we can have empty functions which are optimized away.

View File

@ -85,7 +85,7 @@ AutoTemp:
If your gcode contains a wide spread of extruder velocities, or you realtime change the building speed, the temperature should be changed accordingly. 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. Usually, higher speed requires higher temperature.
This can now be performed by the AutoTemp function This can now be performed by the AutoTemp function
By calling M109 S<mintemp> T<maxtemp> F<factor> you enter the autotemp mode. By calling M109 S<mintemp> B<maxtemp> F<factor> you enter the autotemp mode.
You can leave it by calling M109 without any F. You can leave it by calling M109 without any F.
If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec]. If active, the maximal extruder stepper rate of all buffered moves will be calculated, and named "maxerate" [steps/sec].