MK2 Firmware release.
This commit is contained in:
parent
7361f620d3
commit
a4a80b3eb7
0
Firmware/BlinkM.cpp
Executable file → Normal file
0
Firmware/BlinkM.cpp
Executable file → Normal file
0
Firmware/BlinkM.h
Executable file → Normal file
0
Firmware/BlinkM.h
Executable file → Normal file
@ -5,7 +5,7 @@
|
|||||||
#include "Configuration_prusa.h"
|
#include "Configuration_prusa.h"
|
||||||
|
|
||||||
// Firmware version
|
// Firmware version
|
||||||
#define FW_version "2.2.4d"
|
#define FW_version "3.0.1"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@ -16,6 +16,8 @@
|
|||||||
#define EEPROM_BABYSTEP_Z 4088
|
#define EEPROM_BABYSTEP_Z 4088
|
||||||
#define EEPROM_BABYSTEP_Z_SET 4087
|
#define EEPROM_BABYSTEP_Z_SET 4087
|
||||||
#define EEPROM_BABYSTEP_Z0 4085
|
#define EEPROM_BABYSTEP_Z0 4085
|
||||||
|
#define EEPROM_FILAMENTUSED 4081
|
||||||
|
#define EEPROM_TOTALTIME 4077
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@ -262,6 +264,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||||||
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
#define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)
|
||||||
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
#define Y_MAX_LENGTH (Y_MAX_POS - Y_MIN_POS)
|
||||||
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
#define Z_MAX_LENGTH (Z_MAX_POS - Z_MIN_POS)
|
||||||
|
|
||||||
//============================= Bed Auto Leveling ===========================
|
//============================= Bed Auto Leveling ===========================
|
||||||
|
|
||||||
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
|
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
|
||||||
@ -338,7 +341,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
|
|||||||
|
|
||||||
|
|
||||||
//If you have enabled the Bed Auto Leveling 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.
|
||||||
// When defined, it will:
|
// When defined, it will:
|
||||||
|
0
Firmware/ConfigurationStore.cpp
Executable file → Normal file
0
Firmware/ConfigurationStore.cpp
Executable file → Normal file
0
Firmware/ConfigurationStore.h
Executable file → Normal file
0
Firmware/ConfigurationStore.h
Executable file → Normal file
0
Firmware/Configuration_adv.h
Executable file → Normal file
0
Firmware/Configuration_adv.h
Executable file → Normal file
0
Firmware/DOGMbitmaps.h
Executable file → Normal file
0
Firmware/DOGMbitmaps.h
Executable file → Normal file
0
Firmware/Firmware.ino
Executable file → Normal file
0
Firmware/Firmware.ino
Executable file → Normal file
0
Firmware/LiquidCrystal.cpp
Executable file → Normal file
0
Firmware/LiquidCrystal.cpp
Executable file → Normal file
0
Firmware/LiquidCrystal.h
Executable file → Normal file
0
Firmware/LiquidCrystal.h
Executable file → Normal file
@ -140,18 +140,45 @@ void manage_inactivity(bool ignore_stepper_queue=false);
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
|
#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
|
||||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
#if defined(Z_AXIS_ALWAYS_ON)
|
||||||
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
|
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||||
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
|
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
|
||||||
#else
|
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
|
||||||
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
#else
|
||||||
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
|
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
||||||
#endif
|
#define disable_z() ;
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||||
|
#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
|
||||||
|
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
|
||||||
|
#else
|
||||||
|
#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
||||||
|
#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
#else
|
#else
|
||||||
#define enable_z() ;
|
#define enable_z() ;
|
||||||
#define disable_z() ;
|
#define disable_z() ;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
//#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
|
||||||
|
//#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||||
|
//#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
|
||||||
|
//#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
|
||||||
|
//#else
|
||||||
|
//#define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
|
||||||
|
//#define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; }
|
||||||
|
//#endif
|
||||||
|
//#else
|
||||||
|
//#define enable_z() ;
|
||||||
|
//#define disable_z() ;
|
||||||
|
//#endif
|
||||||
|
|
||||||
|
|
||||||
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
|
#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
|
||||||
#define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
|
#define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
|
||||||
#define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
|
#define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
|
||||||
@ -267,6 +294,17 @@ extern float retract_recover_length, retract_recover_length_swap, retract_recove
|
|||||||
|
|
||||||
extern unsigned long starttime;
|
extern unsigned long starttime;
|
||||||
extern unsigned long stoptime;
|
extern unsigned long stoptime;
|
||||||
|
extern bool is_usb_printing;
|
||||||
|
extern unsigned int usb_printing_counter;
|
||||||
|
|
||||||
|
extern unsigned long total_filament_used;
|
||||||
|
void save_statistics(unsigned long _total_filament_used, unsigned long _total_print_time);
|
||||||
|
extern unsigned int heating_status;
|
||||||
|
extern unsigned int heating_status_counter;
|
||||||
|
extern bool custom_message;
|
||||||
|
extern unsigned int custom_message_type;
|
||||||
|
extern unsigned int custom_message_state;
|
||||||
|
|
||||||
|
|
||||||
// Handling multiple extruders pins
|
// Handling multiple extruders pins
|
||||||
extern uint8_t active_extruder;
|
extern uint8_t active_extruder;
|
||||||
|
0
Firmware/MarlinSerial.cpp
Executable file → Normal file
0
Firmware/MarlinSerial.cpp
Executable file → Normal file
0
Firmware/MarlinSerial.h
Executable file → Normal file
0
Firmware/MarlinSerial.h
Executable file → Normal file
@ -260,11 +260,22 @@ int extruder_multiply[EXTRUDERS] = {100
|
|||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
bool is_usb_printing;
|
||||||
|
bool _doMeshL;
|
||||||
|
unsigned int usb_printing_counter;
|
||||||
|
|
||||||
int lcd_change_fil_state = 0;
|
int lcd_change_fil_state = 0;
|
||||||
int feedmultiplyBckp = 100;
|
int feedmultiplyBckp = 100;
|
||||||
unsigned char lang_selected = 0;
|
unsigned char lang_selected = 0;
|
||||||
|
|
||||||
|
|
||||||
|
unsigned long total_filament_used;
|
||||||
|
unsigned int heating_status;
|
||||||
|
unsigned int heating_status_counter;
|
||||||
|
bool custom_message;
|
||||||
|
unsigned int custom_message_type;
|
||||||
|
unsigned int custom_message_state;
|
||||||
|
|
||||||
bool volumetric_enabled = false;
|
bool volumetric_enabled = false;
|
||||||
float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA
|
float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA
|
||||||
#if EXTRUDERS > 1
|
#if EXTRUDERS > 1
|
||||||
@ -431,6 +442,7 @@ static unsigned long stepper_inactive_time = DEFAULT_STEPPER_DEACTIVE_TIME*1000l
|
|||||||
|
|
||||||
unsigned long starttime=0;
|
unsigned long starttime=0;
|
||||||
unsigned long stoptime=0;
|
unsigned long stoptime=0;
|
||||||
|
unsigned long _usb_timer = 0;
|
||||||
|
|
||||||
static uint8_t tmp_extruder;
|
static uint8_t tmp_extruder;
|
||||||
|
|
||||||
@ -633,19 +645,21 @@ void setup()
|
|||||||
if(mcu & 32) SERIAL_ECHOLNRPGM(MSG_SOFTWARE_RESET);
|
if(mcu & 32) SERIAL_ECHOLNRPGM(MSG_SOFTWARE_RESET);
|
||||||
MCUSR=0;
|
MCUSR=0;
|
||||||
|
|
||||||
SERIAL_ECHORPGM(MSG_MARLIN);
|
//SERIAL_ECHORPGM(MSG_MARLIN);
|
||||||
SERIAL_ECHOLNRPGM(VERSION_STRING);
|
//SERIAL_ECHOLNRPGM(VERSION_STRING);
|
||||||
#ifdef STRING_VERSION_CONFIG_H
|
|
||||||
#ifdef STRING_CONFIG_H_AUTHOR
|
#ifdef STRING_VERSION_CONFIG_H
|
||||||
SERIAL_ECHO_START;
|
#ifdef STRING_CONFIG_H_AUTHOR
|
||||||
SERIAL_ECHORPGM(MSG_CONFIGURATION_VER);
|
SERIAL_ECHO_START;
|
||||||
SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
|
SERIAL_ECHORPGM(MSG_CONFIGURATION_VER);
|
||||||
SERIAL_ECHORPGM(MSG_AUTHOR);
|
SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
|
||||||
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
|
SERIAL_ECHORPGM(MSG_AUTHOR);
|
||||||
SERIAL_ECHOPGM("Compiled: ");
|
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
|
||||||
SERIAL_ECHOLNPGM(__DATE__);
|
SERIAL_ECHOPGM("Compiled: ");
|
||||||
#endif
|
SERIAL_ECHOLNPGM(__DATE__);
|
||||||
#endif
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
SERIAL_ECHO_START;
|
SERIAL_ECHO_START;
|
||||||
SERIAL_ECHORPGM(MSG_FREE_MEMORY);
|
SERIAL_ECHORPGM(MSG_FREE_MEMORY);
|
||||||
SERIAL_ECHO(freeMemory());
|
SERIAL_ECHO(freeMemory());
|
||||||
@ -656,6 +670,9 @@ void setup()
|
|||||||
fromsd[i] = false;
|
fromsd[i] = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
|
// loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
|
||||||
Config_RetrieveSettings();
|
Config_RetrieveSettings();
|
||||||
|
|
||||||
@ -698,6 +715,10 @@ void setup()
|
|||||||
digitalWrite(SERVO0_PIN, LOW); // turn it off
|
digitalWrite(SERVO0_PIN, LOW); // turn it off
|
||||||
#endif // Z_PROBE_SLED
|
#endif // Z_PROBE_SLED
|
||||||
setup_homepin();
|
setup_homepin();
|
||||||
|
|
||||||
|
#if defined(Z_AXIS_ALWAYS_ON)
|
||||||
|
enable_z();
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
//unsigned char first_run_ever=1;
|
//unsigned char first_run_ever=1;
|
||||||
@ -705,6 +726,19 @@ void setup()
|
|||||||
void loop()
|
void loop()
|
||||||
{
|
{
|
||||||
|
|
||||||
|
if (usb_printing_counter > 0 && millis()-_usb_timer > 1000)
|
||||||
|
{
|
||||||
|
is_usb_printing = true;
|
||||||
|
usb_printing_counter--;
|
||||||
|
_usb_timer = millis();
|
||||||
|
}
|
||||||
|
if (usb_printing_counter == 0)
|
||||||
|
{
|
||||||
|
is_usb_printing = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if(buflen < (BUFSIZE-1))
|
if(buflen < (BUFSIZE-1))
|
||||||
get_command();
|
get_command();
|
||||||
#ifdef SDSUPPORT
|
#ifdef SDSUPPORT
|
||||||
@ -724,7 +758,7 @@ void loop()
|
|||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
SERIAL_PROTOCOLLNRPGM(MSG_OK);
|
SERIAL_PROTOCOLLNRPGM(MSG_OK);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@ -824,16 +858,25 @@ void get_command()
|
|||||||
}
|
}
|
||||||
if((strchr(cmdbuffer[bufindw], 'G') != NULL)){
|
if((strchr(cmdbuffer[bufindw], 'G') != NULL)){
|
||||||
strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
|
strchr_pointer = strchr(cmdbuffer[bufindw], 'G');
|
||||||
switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)))){
|
|
||||||
case 0:
|
if (!IS_SD_PRINTING)
|
||||||
case 1:
|
{
|
||||||
case 2:
|
usb_printing_counter = 10;
|
||||||
case 3:
|
is_usb_printing = true;
|
||||||
if (Stopped == true) {
|
}
|
||||||
SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
|
|
||||||
LCD_MESSAGERPGM(MSG_STOPPED);
|
switch((int)((strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL))))
|
||||||
}
|
{
|
||||||
break;
|
case 0:
|
||||||
|
case 1:
|
||||||
|
case 2:
|
||||||
|
case 3:
|
||||||
|
if (Stopped == true)
|
||||||
|
{
|
||||||
|
SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
|
||||||
|
LCD_MESSAGERPGM(MSG_STOPPED);
|
||||||
|
}
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
@ -884,7 +927,8 @@ void get_command()
|
|||||||
int hours, minutes;
|
int hours, minutes;
|
||||||
minutes=(t/60)%60;
|
minutes=(t/60)%60;
|
||||||
hours=t/60/60;
|
hours=t/60/60;
|
||||||
sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
|
save_statistics(total_filament_used, t);
|
||||||
|
sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
|
||||||
SERIAL_ECHO_START;
|
SERIAL_ECHO_START;
|
||||||
SERIAL_ECHOLN(time);
|
SERIAL_ECHOLN(time);
|
||||||
lcd_setstatus(time);
|
lcd_setstatus(time);
|
||||||
@ -1454,7 +1498,6 @@ void process_commands()
|
|||||||
SET_INPUT(FR_SENS);
|
SET_INPUT(FR_SENS);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
unsigned long codenum; //throw away variable
|
unsigned long codenum; //throw away variable
|
||||||
char *starpos = NULL;
|
char *starpos = NULL;
|
||||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||||
@ -1476,7 +1519,9 @@ void process_commands()
|
|||||||
lcd_force_language_selection();
|
lcd_force_language_selection();
|
||||||
} else if(code_seen('Lz')) {
|
} else if(code_seen('Lz')) {
|
||||||
EEPROM_save_B(EEPROM_BABYSTEP_Z,0);
|
EEPROM_save_B(EEPROM_BABYSTEP_Z,0);
|
||||||
}
|
} else if (code_seen('Cal')) {
|
||||||
|
lcd_calibration();
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
else if(code_seen('G'))
|
else if(code_seen('G'))
|
||||||
@ -1662,6 +1707,8 @@ void process_commands()
|
|||||||
|
|
||||||
|
|
||||||
get_coordinates(); // For X Y Z E F
|
get_coordinates(); // For X Y Z E F
|
||||||
|
total_filament_used = total_filament_used + ((destination[E_AXIS] - current_position[E_AXIS])*100);
|
||||||
|
|
||||||
#ifdef FWRETRACT
|
#ifdef FWRETRACT
|
||||||
if(autoretract_enabled)
|
if(autoretract_enabled)
|
||||||
if( !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
|
if( !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) {
|
||||||
@ -1728,15 +1775,18 @@ void process_commands()
|
|||||||
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
|
||||||
|
|
||||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||||
plan_bed_level_matrix.set_to_identity(); //Reset the plane ("erase" all leveling data)
|
plan_bed_level_matrix.set_to_identity(); //Reset the plane ("erase" all leveling data)
|
||||||
#endif //ENABLE_AUTO_BED_LEVELING
|
#endif //ENABLE_AUTO_BED_LEVELING
|
||||||
|
|
||||||
// For mesh bed leveling deactivate the matrix temporarily
|
_doMeshL = false;
|
||||||
|
// For mesh bed leveling deactivate the matrix temporarily
|
||||||
#ifdef MESH_BED_LEVELING
|
#ifdef MESH_BED_LEVELING
|
||||||
mbl.active = 0;
|
mbl.active = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
saved_feedrate = feedrate;
|
saved_feedrate = feedrate;
|
||||||
saved_feedmultiply = feedmultiply;
|
saved_feedmultiply = feedmultiply;
|
||||||
feedmultiply = 100;
|
feedmultiply = 100;
|
||||||
@ -1832,6 +1882,11 @@ void process_commands()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
if (home_all_axis)
|
||||||
|
{
|
||||||
|
_doMeshL = true;
|
||||||
|
}
|
||||||
|
|
||||||
if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
|
if((home_all_axis) || (code_seen(axis_codes[X_AXIS])))
|
||||||
{
|
{
|
||||||
#ifdef DUAL_X_CARRIAGE
|
#ifdef DUAL_X_CARRIAGE
|
||||||
@ -1886,6 +1941,11 @@ void process_commands()
|
|||||||
st_synchronize();
|
st_synchronize();
|
||||||
#endif
|
#endif
|
||||||
#ifdef MESH_BED_LEVELING // If Mesh bed leveling, moxve X&Y to safe position for home
|
#ifdef MESH_BED_LEVELING // If Mesh bed leveling, moxve X&Y to safe position for home
|
||||||
|
if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] ))
|
||||||
|
{
|
||||||
|
HOMEAXIS(X);
|
||||||
|
HOMEAXIS(Y);
|
||||||
|
}
|
||||||
destination[X_AXIS] = MESH_MIN_X - X_PROBE_OFFSET_FROM_EXTRUDER;
|
destination[X_AXIS] = MESH_MIN_X - X_PROBE_OFFSET_FROM_EXTRUDER;
|
||||||
destination[Y_AXIS] = MESH_MIN_Y - Y_PROBE_OFFSET_FROM_EXTRUDER;
|
destination[Y_AXIS] = MESH_MIN_Y - Y_PROBE_OFFSET_FROM_EXTRUDER;
|
||||||
destination[Z_AXIS] = MESH_HOME_Z_SEARCH; // Set destination away from bed
|
destination[Z_AXIS] = MESH_HOME_Z_SEARCH; // Set destination away from bed
|
||||||
@ -1898,9 +1958,8 @@ void process_commands()
|
|||||||
current_position[X_AXIS] = destination[X_AXIS];
|
current_position[X_AXIS] = destination[X_AXIS];
|
||||||
current_position[Y_AXIS] = destination[Y_AXIS];
|
current_position[Y_AXIS] = destination[Y_AXIS];
|
||||||
HOMEAXIS(Z);
|
HOMEAXIS(Z);
|
||||||
|
_doMeshL = true;
|
||||||
|
#else
|
||||||
#else
|
|
||||||
HOMEAXIS(Z);
|
HOMEAXIS(Z);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@ -1982,17 +2041,23 @@ void process_commands()
|
|||||||
#ifndef MESH_BED_LEVELING
|
#ifndef MESH_BED_LEVELING
|
||||||
if(card.sdprinting) {
|
if(card.sdprinting) {
|
||||||
EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoad[2]);
|
EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoad[2]);
|
||||||
|
|
||||||
if(babystepLoad[2] != 0){
|
if(babystepLoad[2] != 0){
|
||||||
|
|
||||||
lcd_adjust_z();
|
lcd_adjust_z();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#ifdef MESH_BED_LEVELING
|
||||||
|
if (code_seen('W'))
|
||||||
|
{
|
||||||
|
_doMeshL = false;
|
||||||
|
SERIAL_ECHOLN("G80 disabled");
|
||||||
|
}
|
||||||
|
|
||||||
|
if ( _doMeshL)
|
||||||
|
{
|
||||||
|
enquecommand_P((PSTR("G80")));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -2000,7 +2065,7 @@ void process_commands()
|
|||||||
case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more 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
|
// Prevent user from running a G29 without first homing in X and Y
|
||||||
@ -2194,9 +2259,17 @@ void process_commands()
|
|||||||
*/
|
*/
|
||||||
case 80:
|
case 80:
|
||||||
{
|
{
|
||||||
|
if (!IS_SD_PRINTING)
|
||||||
|
{
|
||||||
|
custom_message = true;
|
||||||
|
custom_message_type = 1;
|
||||||
|
custom_message_state = (MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) + 10;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// Firstly check if we know where we are
|
// Firstly check if we know where we are
|
||||||
if ( !( axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS] ) ){
|
if ( !( axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS] ) ){
|
||||||
// We don't know where we are!!! HOME!
|
// We don't know where we are! HOME!
|
||||||
enquecommand_P((PSTR("G28")));
|
enquecommand_P((PSTR("G28")));
|
||||||
enquecommand_P((PSTR("G80")));
|
enquecommand_P((PSTR("G80")));
|
||||||
break;
|
break;
|
||||||
@ -2204,7 +2277,6 @@ void process_commands()
|
|||||||
|
|
||||||
mbl.reset();
|
mbl.reset();
|
||||||
|
|
||||||
|
|
||||||
// Cycle through all points and probe them
|
// Cycle through all points and probe them
|
||||||
current_position[X_AXIS] = MESH_MIN_X - X_PROBE_OFFSET_FROM_EXTRUDER;
|
current_position[X_AXIS] = MESH_MIN_X - X_PROBE_OFFSET_FROM_EXTRUDER;
|
||||||
current_position[Y_AXIS] = MESH_MIN_Y - Y_PROBE_OFFSET_FROM_EXTRUDER;
|
current_position[Y_AXIS] = MESH_MIN_Y - Y_PROBE_OFFSET_FROM_EXTRUDER;
|
||||||
@ -2253,7 +2325,10 @@ void process_commands()
|
|||||||
|
|
||||||
|
|
||||||
mbl.set_z(ix, iy, current_position[Z_AXIS]);
|
mbl.set_z(ix, iy, current_position[Z_AXIS]);
|
||||||
|
if (!IS_SD_PRINTING)
|
||||||
|
{
|
||||||
|
custom_message_state--;
|
||||||
|
}
|
||||||
mesh_point++;
|
mesh_point++;
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -2268,18 +2343,16 @@ void process_commands()
|
|||||||
plan_buffer_line(current_position[X_AXIS], current_position[X_AXIS], current_position[Z_AXIS], current_position[E_AXIS], XY_AXIS_FEEDRATE, active_extruder);
|
plan_buffer_line(current_position[X_AXIS], current_position[X_AXIS], current_position[Z_AXIS], current_position[E_AXIS], XY_AXIS_FEEDRATE, active_extruder);
|
||||||
st_synchronize();
|
st_synchronize();
|
||||||
|
|
||||||
if(card.sdprinting) {
|
if(card.sdprinting || is_usb_printing )
|
||||||
|
{
|
||||||
if(eeprom_read_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET) == 0x01){
|
if(eeprom_read_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET) == 0x01)
|
||||||
|
{
|
||||||
EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoad[2]);
|
EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoad[2]);
|
||||||
babystepsTodo[Z_AXIS] = babystepLoad[2];
|
babystepsTodo[Z_AXIS] = babystepLoad[2];
|
||||||
//lcd_adjust_z();
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -2372,6 +2445,11 @@ void process_commands()
|
|||||||
case 87:
|
case 87:
|
||||||
eeprom_write_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET, 0x01);
|
eeprom_write_byte((unsigned char*)EEPROM_BABYSTEP_Z_SET, 0x01);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case 88:
|
||||||
|
break;
|
||||||
|
|
||||||
|
|
||||||
#endif // ENABLE_MESH_BED_LEVELING
|
#endif // ENABLE_MESH_BED_LEVELING
|
||||||
|
|
||||||
|
|
||||||
@ -2987,7 +3065,9 @@ Sigma_Exit:
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
LCD_MESSAGERPGM(MSG_HEATING);
|
LCD_MESSAGERPGM(MSG_HEATING);
|
||||||
#ifdef AUTOTEMP
|
heating_status = 1;
|
||||||
|
|
||||||
|
#ifdef AUTOTEMP
|
||||||
autotemp_enabled=false;
|
autotemp_enabled=false;
|
||||||
#endif
|
#endif
|
||||||
if (code_seen('S')) {
|
if (code_seen('S')) {
|
||||||
@ -3039,6 +3119,7 @@ Sigma_Exit:
|
|||||||
SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
|
SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
|
||||||
SERIAL_PROTOCOLPGM(" E:");
|
SERIAL_PROTOCOLPGM(" E:");
|
||||||
SERIAL_PROTOCOL((int)tmp_extruder);
|
SERIAL_PROTOCOL((int)tmp_extruder);
|
||||||
|
|
||||||
#ifdef TEMP_RESIDENCY_TIME
|
#ifdef TEMP_RESIDENCY_TIME
|
||||||
SERIAL_PROTOCOLPGM(" W:");
|
SERIAL_PROTOCOLPGM(" W:");
|
||||||
if(residencyStart > -1)
|
if(residencyStart > -1)
|
||||||
@ -3064,17 +3145,13 @@ Sigma_Exit:
|
|||||||
if ((residencyStart == -1 && target_direction && (degHotend(tmp_extruder) >= (degTargetHotend(tmp_extruder)-TEMP_WINDOW))) ||
|
if ((residencyStart == -1 && target_direction && (degHotend(tmp_extruder) >= (degTargetHotend(tmp_extruder)-TEMP_WINDOW))) ||
|
||||||
(residencyStart == -1 && !target_direction && (degHotend(tmp_extruder) <= (degTargetHotend(tmp_extruder)+TEMP_WINDOW))) ||
|
(residencyStart == -1 && !target_direction && (degHotend(tmp_extruder) <= (degTargetHotend(tmp_extruder)+TEMP_WINDOW))) ||
|
||||||
(residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS) )
|
(residencyStart > -1 && labs(degHotend(tmp_extruder) - degTargetHotend(tmp_extruder)) > TEMP_HYSTERESIS) )
|
||||||
{
|
{
|
||||||
residencyStart = millis();
|
residencyStart = millis();
|
||||||
}
|
}
|
||||||
#endif //TEMP_RESIDENCY_TIME
|
#endif //TEMP_RESIDENCY_TIME
|
||||||
}
|
}
|
||||||
LCD_MESSAGERPGM(MSG_HEATING_COMPLETE);
|
LCD_MESSAGERPGM(MSG_HEATING_COMPLETE);
|
||||||
|
heating_status = 2;
|
||||||
if(IS_SD_PRINTING){
|
|
||||||
|
|
||||||
lcd_setstatus("SD-PRINTING ");
|
|
||||||
}
|
|
||||||
|
|
||||||
starttime=millis();
|
starttime=millis();
|
||||||
previous_millis_cmd = millis();
|
previous_millis_cmd = millis();
|
||||||
@ -3083,10 +3160,15 @@ Sigma_Exit:
|
|||||||
case 190: // M190 - Wait for bed heater to reach target.
|
case 190: // M190 - Wait for bed heater to reach target.
|
||||||
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
|
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
|
||||||
LCD_MESSAGERPGM(MSG_BED_HEATING);
|
LCD_MESSAGERPGM(MSG_BED_HEATING);
|
||||||
if (code_seen('S')) {
|
heating_status = 3;
|
||||||
|
|
||||||
|
if (code_seen('S'))
|
||||||
|
{
|
||||||
setTargetBed(code_value());
|
setTargetBed(code_value());
|
||||||
CooldownNoWait = true;
|
CooldownNoWait = true;
|
||||||
} else if (code_seen('R')) {
|
}
|
||||||
|
else if (code_seen('R'))
|
||||||
|
{
|
||||||
setTargetBed(code_value());
|
setTargetBed(code_value());
|
||||||
CooldownNoWait = false;
|
CooldownNoWait = false;
|
||||||
}
|
}
|
||||||
@ -3114,10 +3196,8 @@ Sigma_Exit:
|
|||||||
lcd_update();
|
lcd_update();
|
||||||
}
|
}
|
||||||
LCD_MESSAGERPGM(MSG_BED_DONE);
|
LCD_MESSAGERPGM(MSG_BED_DONE);
|
||||||
if(IS_SD_PRINTING){
|
heating_status = 4;
|
||||||
|
|
||||||
lcd_setstatus("SD-PRINTING ");
|
|
||||||
}
|
|
||||||
previous_millis_cmd = millis();
|
previous_millis_cmd = millis();
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
@ -3206,7 +3286,7 @@ Sigma_Exit:
|
|||||||
#endif
|
#endif
|
||||||
#ifdef ULTIPANEL
|
#ifdef ULTIPANEL
|
||||||
powersupply = false;
|
powersupply = false;
|
||||||
LCD_MESSAGERPGM(CAT4(MACHINE_NAME,PSTR(" "),MSG_OFF,PSTR("."))); //!!!!!!!!!!!!!!
|
LCD_MESSAGERPGM(CAT4(CUSTOM_MENDEL_NAME,PSTR(" "),MSG_OFF,PSTR("."))); //!!
|
||||||
|
|
||||||
/*
|
/*
|
||||||
MACHNAME = "Prusa i3"
|
MACHNAME = "Prusa i3"
|
||||||
@ -4139,6 +4219,8 @@ case 404: //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or disp
|
|||||||
#ifdef FILAMENTCHANGEENABLE
|
#ifdef FILAMENTCHANGEENABLE
|
||||||
case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
|
case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
|
||||||
{
|
{
|
||||||
|
st_synchronize();
|
||||||
|
|
||||||
feedmultiplyBckp=feedmultiply;
|
feedmultiplyBckp=feedmultiply;
|
||||||
int8_t TooLowZ = 0;
|
int8_t TooLowZ = 0;
|
||||||
float target[4];
|
float target[4];
|
||||||
@ -4742,6 +4824,7 @@ void calculate_delta(float cartesian[3])
|
|||||||
float dy = y - current_position[Y_AXIS];
|
float dy = y - current_position[Y_AXIS];
|
||||||
float dz = z - current_position[Z_AXIS];
|
float dz = z - current_position[Z_AXIS];
|
||||||
int n_segments = 0;
|
int n_segments = 0;
|
||||||
|
|
||||||
if (mbl.active) {
|
if (mbl.active) {
|
||||||
float len = abs(dx) + abs(dy) + abs(dz);
|
float len = abs(dx) + abs(dy) + abs(dz);
|
||||||
if (len > 0)
|
if (len > 0)
|
||||||
@ -5342,6 +5425,23 @@ bool setTargetedHotend(int code){
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void save_statistics(unsigned long _total_filament_used, unsigned long _total_print_time)
|
||||||
|
{
|
||||||
|
if (eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME) == 255 && eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME + 1) == 255 && eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME + 2) == 255 && eeprom_read_byte((uint8_t *)EEPROM_TOTALTIME + 3) == 255)
|
||||||
|
{
|
||||||
|
eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0);
|
||||||
|
eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
unsigned long _previous_filament = eeprom_read_dword((uint32_t *)EEPROM_FILAMENTUSED);
|
||||||
|
unsigned long _previous_time = eeprom_read_dword((uint32_t *)EEPROM_TOTALTIME);
|
||||||
|
|
||||||
|
eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, _previous_time + (_total_print_time/60));
|
||||||
|
eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, _previous_filament + (_total_filament_used / 1000));
|
||||||
|
|
||||||
|
total_filament_used = 0;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
float calculate_volumetric_multiplier(float diameter) {
|
float calculate_volumetric_multiplier(float diameter) {
|
||||||
float area = .0;
|
float area = .0;
|
||||||
|
0
Firmware/Sd2Card.cpp
Executable file → Normal file
0
Firmware/Sd2Card.cpp
Executable file → Normal file
0
Firmware/Sd2Card.h
Executable file → Normal file
0
Firmware/Sd2Card.h
Executable file → Normal file
0
Firmware/Sd2PinMap.h
Executable file → Normal file
0
Firmware/Sd2PinMap.h
Executable file → Normal file
0
Firmware/SdBaseFile.cpp
Executable file → Normal file
0
Firmware/SdBaseFile.cpp
Executable file → Normal file
0
Firmware/SdBaseFile.h
Executable file → Normal file
0
Firmware/SdBaseFile.h
Executable file → Normal file
0
Firmware/SdFatConfig.h
Executable file → Normal file
0
Firmware/SdFatConfig.h
Executable file → Normal file
0
Firmware/SdFatStructs.h
Executable file → Normal file
0
Firmware/SdFatStructs.h
Executable file → Normal file
0
Firmware/SdFatUtil.cpp
Executable file → Normal file
0
Firmware/SdFatUtil.cpp
Executable file → Normal file
0
Firmware/SdFatUtil.h
Executable file → Normal file
0
Firmware/SdFatUtil.h
Executable file → Normal file
0
Firmware/SdFile.cpp
Executable file → Normal file
0
Firmware/SdFile.cpp
Executable file → Normal file
0
Firmware/SdFile.h
Executable file → Normal file
0
Firmware/SdFile.h
Executable file → Normal file
0
Firmware/SdInfo.h
Executable file → Normal file
0
Firmware/SdInfo.h
Executable file → Normal file
0
Firmware/SdVolume.cpp
Executable file → Normal file
0
Firmware/SdVolume.cpp
Executable file → Normal file
0
Firmware/SdVolume.h
Executable file → Normal file
0
Firmware/SdVolume.h
Executable file → Normal file
0
Firmware/Servo.cpp
Executable file → Normal file
0
Firmware/Servo.cpp
Executable file → Normal file
0
Firmware/Servo.h
Executable file → Normal file
0
Firmware/Servo.h
Executable file → Normal file
0
Firmware/boards.h
Executable file → Normal file
0
Firmware/boards.h
Executable file → Normal file
0
Firmware/cardreader.h
Executable file → Normal file
0
Firmware/cardreader.h
Executable file → Normal file
0
Firmware/digipot_mcp4451.cpp
Executable file → Normal file
0
Firmware/digipot_mcp4451.cpp
Executable file → Normal file
0
Firmware/dogm_font_data_marlin.h
Executable file → Normal file
0
Firmware/dogm_font_data_marlin.h
Executable file → Normal file
0
Firmware/dogm_lcd_implementation.h
Executable file → Normal file
0
Firmware/dogm_lcd_implementation.h
Executable file → Normal file
0
Firmware/fastio.h
Executable file → Normal file
0
Firmware/fastio.h
Executable file → Normal file
@ -12,7 +12,7 @@ function parselang($a) {
|
|||||||
if (!$a[1]) continue;
|
if (!$a[1]) continue;
|
||||||
$v = trim($a[2]);
|
$v = trim($a[2]);
|
||||||
|
|
||||||
$v = str_replace('MACHINE_NAME "','"Prusa i3',$v);
|
//$v = str_replace('MACHINE_NAME "','"Prusa i3',$v);
|
||||||
$v = str_replace('" FIRMWARE_URL "','https://github.com/prusa3d/Prusa-i3-Plus/',$v);
|
$v = str_replace('" FIRMWARE_URL "','https://github.com/prusa3d/Prusa-i3-Plus/',$v);
|
||||||
$v = str_replace('" PROTOCOL_VERSION "','1.0',$v);
|
$v = str_replace('" PROTOCOL_VERSION "','1.0',$v);
|
||||||
$v = str_replace('" STRINGIFY(EXTRUDERS) "','1',$v);
|
$v = str_replace('" STRINGIFY(EXTRUDERS) "','1',$v);
|
||||||
@ -62,7 +62,7 @@ file_put_contents("language_all.h",$out);
|
|||||||
echo ".h created\n";
|
echo ".h created\n";
|
||||||
|
|
||||||
|
|
||||||
$out="#include <avr/pgmspace.h>\n#define LCD_WIDTH 20\nextern unsigned char lang_selected;\n";
|
$out="#include <avr/pgmspace.h>\n#include \"configuration_prusa.h\"\n#define LCD_WIDTH 20\nextern unsigned char lang_selected;\n";
|
||||||
foreach ($langs as $lang) {
|
foreach ($langs as $lang) {
|
||||||
$outa[$lang]="const char* MSG".strtoupper($lang)."[] = {";
|
$outa[$lang]="const char* MSG".strtoupper($lang)."[] = {";
|
||||||
}
|
}
|
||||||
|
@ -46,7 +46,7 @@
|
|||||||
#define FIRMWARE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
|
#define FIRMWARE_URL "https://github.com/fmalpartida/Marlin/tree/SAV-MkI-config"
|
||||||
#else
|
#else
|
||||||
#ifdef CUSTOM_MENDEL_NAME
|
#ifdef CUSTOM_MENDEL_NAME
|
||||||
#define MACHINE_NAME CUSTOM_MENDEL_NAME
|
// #define CUSTOM_MENDEL_NAME CUSTOM_MENDEL_NAME
|
||||||
#else
|
#else
|
||||||
#define MACHINE_NAME "Mendel"
|
#define MACHINE_NAME "Mendel"
|
||||||
#endif
|
#endif
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -127,108 +127,137 @@ extern const char** MSG_ALL[];
|
|||||||
#define MSG_ADJUSTZ MSG_ALL[lang_selected][121]
|
#define MSG_ADJUSTZ MSG_ALL[lang_selected][121]
|
||||||
#define MSG_PICK_Z MSG_ALL[lang_selected][122]
|
#define MSG_PICK_Z MSG_ALL[lang_selected][122]
|
||||||
#define MSG_HOMEYZ MSG_ALL[lang_selected][123]
|
#define MSG_HOMEYZ MSG_ALL[lang_selected][123]
|
||||||
#define MSG_SETTINGS MSG_ALL[lang_selected][124]
|
#define MSG_HOMEYZ_PROGRESS MSG_ALL[lang_selected][124]
|
||||||
#define MSG_PREHEAT MSG_ALL[lang_selected][125]
|
#define MSG_HOMEYZ_DONE MSG_ALL[lang_selected][125]
|
||||||
#define MSG_UNLOAD_FILAMENT MSG_ALL[lang_selected][126]
|
#define MSG_SETTINGS MSG_ALL[lang_selected][126]
|
||||||
#define MSG_LOAD_FILAMENT MSG_ALL[lang_selected][127]
|
#define MSG_PREHEAT MSG_ALL[lang_selected][127]
|
||||||
#define MSG_RECTRACT MSG_ALL[lang_selected][128]
|
#define MSG_UNLOAD_FILAMENT MSG_ALL[lang_selected][128]
|
||||||
#define MSG_ERROR MSG_ALL[lang_selected][129]
|
#define MSG_LOAD_FILAMENT MSG_ALL[lang_selected][129]
|
||||||
#define MSG_PREHEAT_NOZZLE MSG_ALL[lang_selected][130]
|
#define MSG_RECTRACT MSG_ALL[lang_selected][130]
|
||||||
#define MSG_SUPPORT MSG_ALL[lang_selected][131]
|
#define MSG_ERROR MSG_ALL[lang_selected][131]
|
||||||
#define MSG_CORRECTLY MSG_ALL[lang_selected][132]
|
#define MSG_PREHEAT_NOZZLE MSG_ALL[lang_selected][132]
|
||||||
#define MSG_YES MSG_ALL[lang_selected][133]
|
#define MSG_SUPPORT MSG_ALL[lang_selected][133]
|
||||||
#define MSG_NO MSG_ALL[lang_selected][134]
|
#define MSG_CORRECTLY MSG_ALL[lang_selected][134]
|
||||||
#define MSG_NOT_LOADED MSG_ALL[lang_selected][135]
|
#define MSG_YES MSG_ALL[lang_selected][135]
|
||||||
#define MSG_NOT_COLOR MSG_ALL[lang_selected][136]
|
#define MSG_NO MSG_ALL[lang_selected][136]
|
||||||
#define MSG_LOADING_FILAMENT MSG_ALL[lang_selected][137]
|
#define MSG_NOT_LOADED MSG_ALL[lang_selected][137]
|
||||||
#define MSG_PLEASE_WAIT MSG_ALL[lang_selected][138]
|
#define MSG_NOT_COLOR MSG_ALL[lang_selected][138]
|
||||||
#define MSG_LOADING_COLOR MSG_ALL[lang_selected][139]
|
#define MSG_LOADING_FILAMENT MSG_ALL[lang_selected][139]
|
||||||
#define MSG_CHANGE_SUCCESS MSG_ALL[lang_selected][140]
|
#define MSG_PLEASE_WAIT MSG_ALL[lang_selected][140]
|
||||||
#define MSG_PRESS MSG_ALL[lang_selected][141]
|
#define MSG_LOADING_COLOR MSG_ALL[lang_selected][141]
|
||||||
#define MSG_INSERT_FILAMENT MSG_ALL[lang_selected][142]
|
#define MSG_CHANGE_SUCCESS MSG_ALL[lang_selected][142]
|
||||||
#define MSG_CHANGING_FILAMENT MSG_ALL[lang_selected][143]
|
#define MSG_PRESS MSG_ALL[lang_selected][143]
|
||||||
#define MSG_SILENT_MODE_ON MSG_ALL[lang_selected][144]
|
#define MSG_INSERT_FILAMENT MSG_ALL[lang_selected][144]
|
||||||
#define MSG_SILENT_MODE_OFF MSG_ALL[lang_selected][145]
|
#define MSG_CHANGING_FILAMENT MSG_ALL[lang_selected][145]
|
||||||
#define MSG_REBOOT MSG_ALL[lang_selected][146]
|
#define MSG_SILENT_MODE_ON MSG_ALL[lang_selected][146]
|
||||||
#define MSG_TAKE_EFFECT MSG_ALL[lang_selected][147]
|
#define MSG_SILENT_MODE_OFF MSG_ALL[lang_selected][147]
|
||||||
#define MSG_Enqueing MSG_ALL[lang_selected][148]
|
#define MSG_REBOOT MSG_ALL[lang_selected][148]
|
||||||
#define MSG_POWERUP MSG_ALL[lang_selected][149]
|
#define MSG_TAKE_EFFECT MSG_ALL[lang_selected][149]
|
||||||
#define MSG_EXTERNAL_RESET MSG_ALL[lang_selected][150]
|
#define MSG_Enqueing MSG_ALL[lang_selected][150]
|
||||||
#define MSG_BROWNOUT_RESET MSG_ALL[lang_selected][151]
|
#define MSG_POWERUP MSG_ALL[lang_selected][151]
|
||||||
#define MSG_WATCHDOG_RESET MSG_ALL[lang_selected][152]
|
#define MSG_EXTERNAL_RESET MSG_ALL[lang_selected][152]
|
||||||
#define MSG_SOFTWARE_RESET MSG_ALL[lang_selected][153]
|
#define MSG_BROWNOUT_RESET MSG_ALL[lang_selected][153]
|
||||||
#define MSG_AUTHOR MSG_ALL[lang_selected][154]
|
#define MSG_WATCHDOG_RESET MSG_ALL[lang_selected][154]
|
||||||
#define MSG_CONFIGURATION_VER MSG_ALL[lang_selected][155]
|
#define MSG_SOFTWARE_RESET MSG_ALL[lang_selected][155]
|
||||||
#define MSG_FREE_MEMORY MSG_ALL[lang_selected][156]
|
#define MSG_AUTHOR MSG_ALL[lang_selected][156]
|
||||||
#define MSG_PLANNER_BUFFER_BYTES MSG_ALL[lang_selected][157]
|
#define MSG_CONFIGURATION_VER MSG_ALL[lang_selected][157]
|
||||||
#define MSG_OK MSG_ALL[lang_selected][158]
|
#define MSG_FREE_MEMORY MSG_ALL[lang_selected][158]
|
||||||
#define MSG_FILE_SAVED MSG_ALL[lang_selected][159]
|
#define MSG_PLANNER_BUFFER_BYTES MSG_ALL[lang_selected][159]
|
||||||
#define MSG_ERR_LINE_NO MSG_ALL[lang_selected][160]
|
#define MSG_OK MSG_ALL[lang_selected][160]
|
||||||
#define MSG_ERR_CHECKSUM_MISMATCH MSG_ALL[lang_selected][161]
|
#define MSG_FILE_SAVED MSG_ALL[lang_selected][161]
|
||||||
#define MSG_ERR_NO_CHECKSUM MSG_ALL[lang_selected][162]
|
#define MSG_ERR_LINE_NO MSG_ALL[lang_selected][162]
|
||||||
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM MSG_ALL[lang_selected][163]
|
#define MSG_ERR_CHECKSUM_MISMATCH MSG_ALL[lang_selected][163]
|
||||||
#define MSG_FILE_PRINTED MSG_ALL[lang_selected][164]
|
#define MSG_ERR_NO_CHECKSUM MSG_ALL[lang_selected][164]
|
||||||
#define MSG_BEGIN_FILE_LIST MSG_ALL[lang_selected][165]
|
#define MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM MSG_ALL[lang_selected][165]
|
||||||
#define MSG_END_FILE_LIST MSG_ALL[lang_selected][166]
|
#define MSG_FILE_PRINTED MSG_ALL[lang_selected][166]
|
||||||
#define MSG_M104_INVALID_EXTRUDER MSG_ALL[lang_selected][167]
|
#define MSG_BEGIN_FILE_LIST MSG_ALL[lang_selected][167]
|
||||||
#define MSG_M105_INVALID_EXTRUDER MSG_ALL[lang_selected][168]
|
#define MSG_END_FILE_LIST MSG_ALL[lang_selected][168]
|
||||||
#define MSG_M200_INVALID_EXTRUDER MSG_ALL[lang_selected][169]
|
#define MSG_M104_INVALID_EXTRUDER MSG_ALL[lang_selected][169]
|
||||||
#define MSG_M218_INVALID_EXTRUDER MSG_ALL[lang_selected][170]
|
#define MSG_M105_INVALID_EXTRUDER MSG_ALL[lang_selected][170]
|
||||||
#define MSG_M221_INVALID_EXTRUDER MSG_ALL[lang_selected][171]
|
#define MSG_M200_INVALID_EXTRUDER MSG_ALL[lang_selected][171]
|
||||||
#define MSG_ERR_NO_THERMISTORS MSG_ALL[lang_selected][172]
|
#define MSG_M218_INVALID_EXTRUDER MSG_ALL[lang_selected][172]
|
||||||
#define MSG_M109_INVALID_EXTRUDER MSG_ALL[lang_selected][173]
|
#define MSG_M221_INVALID_EXTRUDER MSG_ALL[lang_selected][173]
|
||||||
#define MSG_HEATING MSG_ALL[lang_selected][174]
|
#define MSG_ERR_NO_THERMISTORS MSG_ALL[lang_selected][174]
|
||||||
#define MSG_HEATING_COMPLETE MSG_ALL[lang_selected][175]
|
#define MSG_M109_INVALID_EXTRUDER MSG_ALL[lang_selected][175]
|
||||||
#define MSG_BED_HEATING MSG_ALL[lang_selected][176]
|
#define MSG_HEATING MSG_ALL[lang_selected][176]
|
||||||
#define MSG_BED_DONE MSG_ALL[lang_selected][177]
|
#define MSG_HEATING_COMPLETE MSG_ALL[lang_selected][177]
|
||||||
#define MSG_M115_REPORT MSG_ALL[lang_selected][178]
|
#define MSG_BED_HEATING MSG_ALL[lang_selected][178]
|
||||||
#define MSG_COUNT_X MSG_ALL[lang_selected][179]
|
#define MSG_BED_DONE MSG_ALL[lang_selected][179]
|
||||||
#define MSG_ERR_KILLED MSG_ALL[lang_selected][180]
|
#define MSG_M115_REPORT MSG_ALL[lang_selected][180]
|
||||||
#define MSG_ERR_STOPPED MSG_ALL[lang_selected][181]
|
#define MSG_COUNT_X MSG_ALL[lang_selected][181]
|
||||||
#define MSG_RESEND MSG_ALL[lang_selected][182]
|
#define MSG_ERR_KILLED MSG_ALL[lang_selected][182]
|
||||||
#define MSG_UNKNOWN_COMMAND MSG_ALL[lang_selected][183]
|
#define MSG_ERR_STOPPED MSG_ALL[lang_selected][183]
|
||||||
#define MSG_ACTIVE_EXTRUDER MSG_ALL[lang_selected][184]
|
#define MSG_RESEND MSG_ALL[lang_selected][184]
|
||||||
#define MSG_INVALID_EXTRUDER MSG_ALL[lang_selected][185]
|
#define MSG_UNKNOWN_COMMAND MSG_ALL[lang_selected][185]
|
||||||
#define MSG_X_MIN MSG_ALL[lang_selected][186]
|
#define MSG_ACTIVE_EXTRUDER MSG_ALL[lang_selected][186]
|
||||||
#define MSG_X_MAX MSG_ALL[lang_selected][187]
|
#define MSG_INVALID_EXTRUDER MSG_ALL[lang_selected][187]
|
||||||
#define MSG_Y_MIN MSG_ALL[lang_selected][188]
|
#define MSG_X_MIN MSG_ALL[lang_selected][188]
|
||||||
#define MSG_Y_MAX MSG_ALL[lang_selected][189]
|
#define MSG_X_MAX MSG_ALL[lang_selected][189]
|
||||||
#define MSG_Z_MIN MSG_ALL[lang_selected][190]
|
#define MSG_Y_MIN MSG_ALL[lang_selected][190]
|
||||||
#define MSG_Z_MAX MSG_ALL[lang_selected][191]
|
#define MSG_Y_MAX MSG_ALL[lang_selected][191]
|
||||||
#define MSG_M119_REPORT MSG_ALL[lang_selected][192]
|
#define MSG_Z_MIN MSG_ALL[lang_selected][192]
|
||||||
#define MSG_ENDSTOP_HIT MSG_ALL[lang_selected][193]
|
#define MSG_Z_MAX MSG_ALL[lang_selected][193]
|
||||||
#define MSG_ENDSTOP_OPEN MSG_ALL[lang_selected][194]
|
#define MSG_M119_REPORT MSG_ALL[lang_selected][194]
|
||||||
#define MSG_HOTEND_OFFSET MSG_ALL[lang_selected][195]
|
#define MSG_ENDSTOP_HIT MSG_ALL[lang_selected][195]
|
||||||
#define MSG_SD_CANT_OPEN_SUBDIR MSG_ALL[lang_selected][196]
|
#define MSG_ENDSTOP_OPEN MSG_ALL[lang_selected][196]
|
||||||
#define MSG_SD_INIT_FAIL MSG_ALL[lang_selected][197]
|
#define MSG_HOTEND_OFFSET MSG_ALL[lang_selected][197]
|
||||||
#define MSG_SD_VOL_INIT_FAIL MSG_ALL[lang_selected][198]
|
#define MSG_SD_CANT_OPEN_SUBDIR MSG_ALL[lang_selected][198]
|
||||||
#define MSG_SD_OPENROOT_FAIL MSG_ALL[lang_selected][199]
|
#define MSG_SD_INIT_FAIL MSG_ALL[lang_selected][199]
|
||||||
#define MSG_SD_CARD_OK MSG_ALL[lang_selected][200]
|
#define MSG_SD_VOL_INIT_FAIL MSG_ALL[lang_selected][200]
|
||||||
#define MSG_SD_WORKDIR_FAIL MSG_ALL[lang_selected][201]
|
#define MSG_SD_OPENROOT_FAIL MSG_ALL[lang_selected][201]
|
||||||
#define MSG_SD_OPEN_FILE_FAIL MSG_ALL[lang_selected][202]
|
#define MSG_SD_CARD_OK MSG_ALL[lang_selected][202]
|
||||||
#define MSG_SD_FILE_OPENED MSG_ALL[lang_selected][203]
|
#define MSG_SD_WORKDIR_FAIL MSG_ALL[lang_selected][203]
|
||||||
#define MSG_SD_SIZE MSG_ALL[lang_selected][204]
|
#define MSG_SD_OPEN_FILE_FAIL MSG_ALL[lang_selected][204]
|
||||||
#define MSG_SD_FILE_SELECTED MSG_ALL[lang_selected][205]
|
#define MSG_SD_FILE_OPENED MSG_ALL[lang_selected][205]
|
||||||
#define MSG_SD_WRITE_TO_FILE MSG_ALL[lang_selected][206]
|
#define MSG_SD_SIZE MSG_ALL[lang_selected][206]
|
||||||
#define MSG_SD_PRINTING_BYTE MSG_ALL[lang_selected][207]
|
#define MSG_SD_FILE_SELECTED MSG_ALL[lang_selected][207]
|
||||||
#define MSG_SD_NOT_PRINTING MSG_ALL[lang_selected][208]
|
#define MSG_SD_WRITE_TO_FILE MSG_ALL[lang_selected][208]
|
||||||
#define MSG_SD_ERR_WRITE_TO_FILE MSG_ALL[lang_selected][209]
|
#define MSG_SD_PRINTING_BYTE MSG_ALL[lang_selected][209]
|
||||||
#define MSG_SD_CANT_ENTER_SUBDIR MSG_ALL[lang_selected][210]
|
#define MSG_SD_NOT_PRINTING MSG_ALL[lang_selected][210]
|
||||||
#define MSG_STEPPER_TOO_HIGH MSG_ALL[lang_selected][211]
|
#define MSG_SD_ERR_WRITE_TO_FILE MSG_ALL[lang_selected][211]
|
||||||
#define MSG_ENDSTOPS_HIT MSG_ALL[lang_selected][212]
|
#define MSG_SD_CANT_ENTER_SUBDIR MSG_ALL[lang_selected][212]
|
||||||
#define MSG_ERR_COLD_EXTRUDE_STOP MSG_ALL[lang_selected][213]
|
#define MSG_STEPPER_TOO_HIGH MSG_ALL[lang_selected][213]
|
||||||
#define MSG_ERR_LONG_EXTRUDE_STOP MSG_ALL[lang_selected][214]
|
#define MSG_ENDSTOPS_HIT MSG_ALL[lang_selected][214]
|
||||||
#define MSG_BABYSTEPPING_X MSG_ALL[lang_selected][215]
|
#define MSG_ERR_COLD_EXTRUDE_STOP MSG_ALL[lang_selected][215]
|
||||||
#define MSG_BABYSTEPPING_Y MSG_ALL[lang_selected][216]
|
#define MSG_ERR_LONG_EXTRUDE_STOP MSG_ALL[lang_selected][216]
|
||||||
#define MSG_BABYSTEPPING_Z MSG_ALL[lang_selected][217]
|
#define MSG_BABYSTEPPING_X MSG_ALL[lang_selected][217]
|
||||||
#define MSG_SERIAL_ERROR_MENU_STRUCTURE MSG_ALL[lang_selected][218]
|
#define MSG_BABYSTEPPING_Y MSG_ALL[lang_selected][218]
|
||||||
#define MSG_LANGUAGE_NAME MSG_ALL[lang_selected][219]
|
#define MSG_BABYSTEPPING_Z MSG_ALL[lang_selected][219]
|
||||||
#define MSG_LANGUAGE_SELECT MSG_ALL[lang_selected][220]
|
#define MSG_SERIAL_ERROR_MENU_STRUCTURE MSG_ALL[lang_selected][220]
|
||||||
#define MSG_PRUSA3D MSG_ALL[lang_selected][221]
|
#define MSG_LANGUAGE_NAME MSG_ALL[lang_selected][221]
|
||||||
#define MSG_PRUSA3D_FORUM MSG_ALL[lang_selected][222]
|
#define MSG_LANGUAGE_SELECT MSG_ALL[lang_selected][222]
|
||||||
#define MSG_PRUSA3D_HOWTO MSG_ALL[lang_selected][223]
|
#define MSG_PRUSA3D MSG_ALL[lang_selected][223]
|
||||||
#define LANGUAGE_NAME 219
|
#define MSG_PRUSA3D_FORUM MSG_ALL[lang_selected][224]
|
||||||
#define LANGUAGE_SELECT 220
|
#define MSG_PRUSA3D_HOWTO MSG_ALL[lang_selected][225]
|
||||||
|
#define MSG_SELFTEST_ERROR MSG_ALL[lang_selected][226]
|
||||||
|
#define MSG_SELFTEST_PLEASECHECK MSG_ALL[lang_selected][227]
|
||||||
|
#define MSG_SELFTEST_NOTCONNECTED MSG_ALL[lang_selected][228]
|
||||||
|
#define MSG_SELFTEST_HEATERTHERMISTOR MSG_ALL[lang_selected][229]
|
||||||
|
#define MSG_SELFTEST_BEDHEATER MSG_ALL[lang_selected][230]
|
||||||
|
#define MSG_SELFTEST_WIRINGERROR MSG_ALL[lang_selected][231]
|
||||||
|
#define MSG_SELFTEST_ENDSTOPS MSG_ALL[lang_selected][232]
|
||||||
|
#define MSG_SELFTEST_MOTOR MSG_ALL[lang_selected][233]
|
||||||
|
#define MSG_SELFTEST_ENDSTOP MSG_ALL[lang_selected][234]
|
||||||
|
#define MSG_SELFTEST_ENDSTOP_NOTHIT MSG_ALL[lang_selected][235]
|
||||||
|
#define MSG_SELFTEST_OK MSG_ALL[lang_selected][236]
|
||||||
|
#define MSG_STATS_TOTALFILAMENT MSG_ALL[lang_selected][237]
|
||||||
|
#define MSG_STATS_TOTALPRINTTIME MSG_ALL[lang_selected][238]
|
||||||
|
#define MSG_STATS_FILAMENTUSED MSG_ALL[lang_selected][239]
|
||||||
|
#define MSG_STATS_PRINTTIME MSG_ALL[lang_selected][240]
|
||||||
|
#define MSG_SELFTEST_START MSG_ALL[lang_selected][241]
|
||||||
|
#define MSG_SELFTEST_CHECK_ENDSTOPS MSG_ALL[lang_selected][242]
|
||||||
|
#define MSG_SELFTEST_CHECK_HOTEND MSG_ALL[lang_selected][243]
|
||||||
|
#define MSG_SELFTEST_CHECK_X MSG_ALL[lang_selected][244]
|
||||||
|
#define MSG_SELFTEST_CHECK_Y MSG_ALL[lang_selected][245]
|
||||||
|
#define MSG_SELFTEST_CHECK_Z MSG_ALL[lang_selected][246]
|
||||||
|
#define MSG_SELFTEST_CHECK_BED MSG_ALL[lang_selected][247]
|
||||||
|
#define MSG_SELFTEST_CHECK_ALLCORRECT MSG_ALL[lang_selected][248]
|
||||||
|
#define MSG_SELFTEST MSG_ALL[lang_selected][249]
|
||||||
|
#define MSG_SELFTEST_FAILED MSG_ALL[lang_selected][250]
|
||||||
|
#define MSG_STATISTICS MSG_ALL[lang_selected][251]
|
||||||
|
#define MSG_USB_PRINTING MSG_ALL[lang_selected][252]
|
||||||
|
#define LANGUAGE_NAME 221
|
||||||
|
#define LANGUAGE_SELECT 222
|
||||||
#define LANG_NUM 5
|
#define LANG_NUM 5
|
||||||
char* CAT2(const char *s1,const char *s2);
|
char* CAT2(const char *s1,const char *s2);
|
||||||
char* CAT4(const char *s1,const char *s2,const char *s3,const char *s4);
|
char* CAT4(const char *s1,const char *s2,const char *s3,const char *s4);
|
||||||
|
48
Firmware/language_cz.h
Executable file → Normal file
48
Firmware/language_cz.h
Executable file → Normal file
@ -8,7 +8,7 @@
|
|||||||
#ifndef LANGUAGE_CZ_H
|
#ifndef LANGUAGE_CZ_H
|
||||||
#define LANGUAGE_CZ_H
|
#define LANGUAGE_CZ_H
|
||||||
|
|
||||||
#define WELCOME_MSG MACHINE_NAME " pripravena"
|
#define WELCOME_MSG CUSTOM_MENDEL_NAME " ok"
|
||||||
#define MSG_SD_INSERTED "Karta vlozena"
|
#define MSG_SD_INSERTED "Karta vlozena"
|
||||||
#define MSG_SD_REMOVED "Karta vyjmuta"
|
#define MSG_SD_REMOVED "Karta vyjmuta"
|
||||||
#define MSG_MAIN "Hlavni nabidka"
|
#define MSG_MAIN "Hlavni nabidka"
|
||||||
@ -133,6 +133,9 @@
|
|||||||
#define MSG_PICK_Z "Vyberte vytisk"
|
#define MSG_PICK_Z "Vyberte vytisk"
|
||||||
|
|
||||||
#define MSG_HOMEYZ "Kalibrovat Z"
|
#define MSG_HOMEYZ "Kalibrovat Z"
|
||||||
|
#define MSG_HOMEYZ_PROGRESS "Kalibruji Z"
|
||||||
|
#define MSG_HOMEYZ_DONE "Kalibrace OK"
|
||||||
|
|
||||||
#define MSG_SETTINGS "Nastaveni"
|
#define MSG_SETTINGS "Nastaveni"
|
||||||
#define MSG_PREHEAT "Predehrev"
|
#define MSG_PREHEAT "Predehrev"
|
||||||
#define MSG_UNLOAD_FILAMENT "Vyjmout filament"
|
#define MSG_UNLOAD_FILAMENT "Vyjmout filament"
|
||||||
@ -186,11 +189,11 @@
|
|||||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||||
#define MSG_HEATING "Zahrivani..."
|
#define MSG_HEATING "Zahrivani"
|
||||||
#define MSG_HEATING_COMPLETE "Zahrivani OK."
|
#define MSG_HEATING_COMPLETE "Zahrivani OK."
|
||||||
#define MSG_BED_HEATING "Zahrivani bed..."
|
#define MSG_BED_HEATING "Zahrivani bed"
|
||||||
#define MSG_BED_DONE "Bed OK."
|
#define MSG_BED_DONE "Bed OK."
|
||||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||||
#define MSG_COUNT_X " Count X: "
|
#define MSG_COUNT_X " Count X: "
|
||||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||||
@ -236,8 +239,43 @@
|
|||||||
|
|
||||||
#define MSG_LANGUAGE_NAME "Cestina"
|
#define MSG_LANGUAGE_NAME "Cestina"
|
||||||
#define MSG_LANGUAGE_SELECT "Vyber jazyka "
|
#define MSG_LANGUAGE_SELECT "Vyber jazyka "
|
||||||
#define MSG_PRUSA3D "prusa3d.cz"
|
#define MSG_PRUSA3D "prusa3d.cz"
|
||||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.cz"
|
#define MSG_PRUSA3D_FORUM "forum.prusa3d.cz"
|
||||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.cz"
|
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.cz"
|
||||||
|
|
||||||
|
#define MSG_HOMEYZ "Kalibrovat Z"
|
||||||
|
#define MSG_HOMEYZ_PROGRESS "Kalibruji Z"
|
||||||
|
#define MSG_HOMEYZ_DONE "Kalibrace OK"
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_ERROR "Selftest error !"
|
||||||
|
#define MSG_SELFTEST_PLEASECHECK "Zkontrolujte :"
|
||||||
|
#define MSG_SELFTEST_NOTCONNECTED "Nezapojeno "
|
||||||
|
#define MSG_SELFTEST_HEATERTHERMISTOR "Heater/Thermistor"
|
||||||
|
#define MSG_SELFTEST_BEDHEATER "Bed / Heater"
|
||||||
|
#define MSG_SELFTEST_WIRINGERROR "Chyba zapojeni"
|
||||||
|
#define MSG_SELFTEST_ENDSTOPS "Endstops"
|
||||||
|
#define MSG_SELFTEST_MOTOR "Motor"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP "Endstop"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||||
|
#define MSG_SELFTEST_OK "Self test OK"
|
||||||
|
|
||||||
|
#define MSG_STATS_TOTALFILAMENT "Filament celkem :"
|
||||||
|
#define MSG_STATS_TOTALPRINTTIME "Celkovy cas :"
|
||||||
|
#define MSG_STATS_FILAMENTUSED "Filament : "
|
||||||
|
#define MSG_STATS_PRINTTIME "Cas tisku : "
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_START "Self test start "
|
||||||
|
#define MSG_SELFTEST_CHECK_ENDSTOPS "Kontrola endstops"
|
||||||
|
#define MSG_SELFTEST_CHECK_HOTEND "Kontrola hotend "
|
||||||
|
#define MSG_SELFTEST_CHECK_X "Kontrola X axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_Y "Kontrola Y axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_Z "Kontrola Z axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_BED "Kontrola bed "
|
||||||
|
#define MSG_SELFTEST_CHECK_ALLCORRECT "Vse OK "
|
||||||
|
#define MSG_SELFTEST "Selftest "
|
||||||
|
#define MSG_SELFTEST_FAILED "Selftest selhal "
|
||||||
|
|
||||||
|
#define MSG_STATISTICS "Statistika "
|
||||||
|
#define MSG_USB_PRINTING "Tisk z USB "
|
||||||
|
|
||||||
#endif // LANGUAGE_EN_H
|
#endif // LANGUAGE_EN_H
|
||||||
|
49
Firmware/language_en.h
Executable file → Normal file
49
Firmware/language_en.h
Executable file → Normal file
@ -8,7 +8,7 @@
|
|||||||
#ifndef LANGUAGE_EN_H
|
#ifndef LANGUAGE_EN_H
|
||||||
#define LANGUAGE_EN_H
|
#define LANGUAGE_EN_H
|
||||||
|
|
||||||
#define WELCOME_MSG MACHINE_NAME " ready."
|
#define WELCOME_MSG CUSTOM_MENDEL_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"
|
||||||
@ -132,7 +132,6 @@
|
|||||||
#define MSG_ADJUSTZ "Auto adjust Z ?"
|
#define MSG_ADJUSTZ "Auto adjust Z ?"
|
||||||
#define MSG_PICK_Z "Pick print"
|
#define MSG_PICK_Z "Pick print"
|
||||||
|
|
||||||
#define MSG_HOMEYZ "Calibrate Z"
|
|
||||||
#define MSG_SETTINGS "Settings"
|
#define MSG_SETTINGS "Settings"
|
||||||
#define MSG_PREHEAT "Preheat"
|
#define MSG_PREHEAT "Preheat"
|
||||||
#define MSG_UNLOAD_FILAMENT "Unload filament"
|
#define MSG_UNLOAD_FILAMENT "Unload filament"
|
||||||
@ -187,11 +186,11 @@
|
|||||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||||
#define MSG_HEATING "Heating..."
|
#define MSG_HEATING "Heating"
|
||||||
#define MSG_HEATING_COMPLETE "Heating done."
|
#define MSG_HEATING_COMPLETE "Heating done."
|
||||||
#define MSG_BED_HEATING "Bed Heating."
|
#define MSG_BED_HEATING "Bed Heating"
|
||||||
#define MSG_BED_DONE "Bed done."
|
#define MSG_BED_DONE "Bed done"
|
||||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||||
#define MSG_COUNT_X " Count X: "
|
#define MSG_COUNT_X " Count X: "
|
||||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||||
@ -237,9 +236,41 @@
|
|||||||
|
|
||||||
#define MSG_LANGUAGE_NAME "English"
|
#define MSG_LANGUAGE_NAME "English"
|
||||||
#define MSG_LANGUAGE_SELECT "Select language "
|
#define MSG_LANGUAGE_SELECT "Select language "
|
||||||
#define MSG_PRUSA3D "prusa3d.com"
|
#define MSG_PRUSA3D "prusa3d.com"
|
||||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_ERROR "Selftest error !"
|
||||||
|
#define MSG_SELFTEST_PLEASECHECK "Please check :"
|
||||||
|
#define MSG_SELFTEST_NOTCONNECTED "Not connected"
|
||||||
|
#define MSG_SELFTEST_HEATERTHERMISTOR "Heater/Thermistor"
|
||||||
|
#define MSG_SELFTEST_BEDHEATER "Bed / Heater"
|
||||||
|
#define MSG_SELFTEST_WIRINGERROR "Wiring error"
|
||||||
|
#define MSG_SELFTEST_ENDSTOPS "Endstops"
|
||||||
|
#define MSG_SELFTEST_MOTOR "Motor"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP "Endstop"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||||
|
#define MSG_SELFTEST_OK "Self test OK"
|
||||||
|
#define MSG_STATS_TOTALFILAMENT "Total filament :"
|
||||||
|
#define MSG_STATS_TOTALPRINTTIME "Total print time :"
|
||||||
|
#define MSG_STATS_FILAMENTUSED "Filament used: "
|
||||||
|
#define MSG_STATS_PRINTTIME "Print time: "
|
||||||
|
#define MSG_SELFTEST_START "Self test start "
|
||||||
|
#define MSG_SELFTEST_CHECK_ENDSTOPS "Checking endstops"
|
||||||
|
#define MSG_SELFTEST_CHECK_HOTEND "Checking hotend "
|
||||||
|
#define MSG_SELFTEST_CHECK_X "Checking X axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_Y "Checking Y axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_Z "Checking Z axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_BED "Checking bed "
|
||||||
|
#define MSG_SELFTEST_CHECK_ALLCORRECT "All correct "
|
||||||
|
#define MSG_SELFTEST "Selftest "
|
||||||
|
#define MSG_SELFTEST_FAILED "Selftest failed "
|
||||||
|
#define MSG_STATISTICS "Statistics "
|
||||||
|
#define MSG_USB_PRINTING "USB printing "
|
||||||
|
#define MSG_HOMEYZ "Calibrate Z"
|
||||||
|
#define MSG_HOMEYZ_PROGRESS "Calibrating Z"
|
||||||
|
#define MSG_HOMEYZ_DONE "Calibration done"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
#endif // LANGUAGE_EN_H
|
#endif // LANGUAGE_EN_H
|
||||||
|
@ -8,7 +8,7 @@
|
|||||||
#ifndef LANGUAGE_ES_H
|
#ifndef LANGUAGE_ES_H
|
||||||
#define LANGUAGE_ES_H
|
#define LANGUAGE_ES_H
|
||||||
|
|
||||||
#define WELCOME_MSG MACHINE_NAME " lista"
|
#define WELCOME_MSG CUSTOM_MENDEL_NAME " lista"
|
||||||
#define MSG_SD_INSERTED "Tarjeta colocada"
|
#define MSG_SD_INSERTED "Tarjeta colocada"
|
||||||
#define MSG_SD_REMOVED "Tarjeta retirada"
|
#define MSG_SD_REMOVED "Tarjeta retirada"
|
||||||
#define MSG_MAIN "Menu principal"
|
#define MSG_MAIN "Menu principal"
|
||||||
@ -44,26 +44,26 @@
|
|||||||
#define MSG_BABYSTEP_Z "Micropaso Z"
|
#define MSG_BABYSTEP_Z "Micropaso Z"
|
||||||
#define MSG_ADJUSTZ "Auto Micropaso Z?"
|
#define MSG_ADJUSTZ "Auto Micropaso Z?"
|
||||||
#define MSG_PICK_Z "Vyberte vytisk"
|
#define MSG_PICK_Z "Vyberte vytisk"
|
||||||
#define MSG_HOMEYZ "Graduar Z"
|
|
||||||
#define MSG_SETTINGS "Ajuste"
|
#define MSG_SETTINGS "Ajuste"
|
||||||
#define MSG_PREHEAT "Precalentar"
|
#define MSG_PREHEAT "Precalentar"
|
||||||
#define MSG_UNLOAD_FILAMENT "Sacar filamento"
|
#define MSG_UNLOAD_FILAMENT "Sacar filamento"
|
||||||
#define MSG_LOAD_FILAMENT "Introducir filamento"
|
#define MSG_LOAD_FILAMENT "Introducir filamento"
|
||||||
#define MSG_ERROR "ERROR:"
|
#define MSG_ERROR "ERROR:"
|
||||||
#define MSG_PREHEAT_NOZZLE "Precal. extrusor!"
|
#define MSG_PREHEAT_NOZZLE "Precal. extrusor!"
|
||||||
#define MSG_SUPPORT "Support"
|
#define MSG_SUPPORT "Support"
|
||||||
#define MSG_CORRECTLY "Cambiado correc.?"
|
#define MSG_CORRECTLY "Cambiado correc.?"
|
||||||
#define MSG_YES "Si"
|
#define MSG_YES "Si"
|
||||||
#define MSG_NO "No"
|
#define MSG_NO "No"
|
||||||
#define MSG_NOT_LOADED "Fil. no cargado"
|
#define MSG_NOT_LOADED "Fil. no cargado"
|
||||||
#define MSG_NOT_COLOR "Color no claro"
|
#define MSG_NOT_COLOR "Color no claro"
|
||||||
#define MSG_LOADING_FILAMENT "Cargando fil."
|
#define MSG_LOADING_FILAMENT "Cargando fil."
|
||||||
#define MSG_PLEASE_WAIT "Espera"
|
#define MSG_PLEASE_WAIT "Espera"
|
||||||
#define MSG_LOADING_COLOR "Cargando color"
|
#define MSG_LOADING_COLOR "Cargando color"
|
||||||
#define MSG_CHANGE_SUCCESS "Cambiar bien!"
|
#define MSG_CHANGE_SUCCESS "Cambiar bien!"
|
||||||
#define MSG_PRESS "Y pulse el mando"
|
#define MSG_PRESS "Y pulse el mando"
|
||||||
#define MSG_INSERT_FILAMENT "Inserta filamento"
|
#define MSG_INSERT_FILAMENT "Inserta filamento"
|
||||||
#define MSG_CHANGING_FILAMENT "Cambiando fil.!"
|
#define MSG_CHANGING_FILAMENT "Cambiando fil.!"
|
||||||
#define MSG_SILENT_MODE_ON "Modo [silencio]"
|
#define MSG_SILENT_MODE_ON "Modo [silencio]"
|
||||||
#define MSG_SILENT_MODE_OFF "Modo [mas fuerza]"
|
#define MSG_SILENT_MODE_OFF "Modo [mas fuerza]"
|
||||||
#define MSG_REBOOT "Reiniciar la imp."
|
#define MSG_REBOOT "Reiniciar la imp."
|
||||||
@ -74,7 +74,7 @@
|
|||||||
#define MSG_BED_DONE "Base listo."
|
#define MSG_BED_DONE "Base listo."
|
||||||
#define MSG_LANGUAGE_NAME "Espanol"
|
#define MSG_LANGUAGE_NAME "Espanol"
|
||||||
#define MSG_LANGUAGE_SELECT "Cambia la lengua "
|
#define MSG_LANGUAGE_SELECT "Cambia la lengua "
|
||||||
#define MSG_PRUSA3D "prusa3d.com"
|
#define MSG_PRUSA3D "prusa3d.com"
|
||||||
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
#define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||||
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
#define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||||
|
|
||||||
@ -107,7 +107,7 @@
|
|||||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||||
#define MSG_COUNT_X " Count X: "
|
#define MSG_COUNT_X " Count X: "
|
||||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||||
@ -237,4 +237,40 @@
|
|||||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||||
#define MSG_RECTRACT "Rectract"
|
#define MSG_RECTRACT "Rectract"
|
||||||
|
|
||||||
|
#define MSG_HOMEYZ "Calibrar Z"
|
||||||
|
#define MSG_HOMEYZ_PROGRESS "Calibrando Z"
|
||||||
|
#define MSG_HOMEYZ_DONE "Calibracion OK"
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_ERROR "Autotest error!"
|
||||||
|
#define MSG_SELFTEST_PLEASECHECK "Controla :"
|
||||||
|
#define MSG_SELFTEST_NOTCONNECTED "No hay conexion "
|
||||||
|
#define MSG_SELFTEST_HEATERTHERMISTOR "Calent./Termistor"
|
||||||
|
#define MSG_SELFTEST_BEDHEATER "Cama/Calentador"
|
||||||
|
#define MSG_SELFTEST_WIRINGERROR "Error de conexión"
|
||||||
|
#define MSG_SELFTEST_ENDSTOPS "Topes final"
|
||||||
|
#define MSG_SELFTEST_MOTOR "Motor"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP "Tope final"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Tope fin. no toc."
|
||||||
|
#define MSG_SELFTEST_OK "Self test OK"
|
||||||
|
|
||||||
|
#define MSG_STATS_TOTALFILAMENT "Filamento total:"
|
||||||
|
#define MSG_STATS_TOTALPRINTTIME "Tiempo total :"
|
||||||
|
#define MSG_STATS_FILAMENTUSED "Filamento : "
|
||||||
|
#define MSG_STATS_PRINTTIME "Tiempo de imp.:"
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_START "Autotest salida"
|
||||||
|
#define MSG_SELFTEST_CHECK_ENDSTOPS "Cont. topes final"
|
||||||
|
#define MSG_SELFTEST_CHECK_HOTEND "Control hotend "
|
||||||
|
#define MSG_SELFTEST_CHECK_X "Control del eje X"
|
||||||
|
#define MSG_SELFTEST_CHECK_Y "Control del eje Y"
|
||||||
|
#define MSG_SELFTEST_CHECK_Z "Control del eje Z"
|
||||||
|
#define MSG_SELFTEST_CHECK_BED "Control de cama"
|
||||||
|
#define MSG_SELFTEST_CHECK_ALLCORRECT "Todo bie "
|
||||||
|
#define MSG_SELFTEST "Autotest"
|
||||||
|
#define MSG_SELFTEST_FAILED "Autotest fallado"
|
||||||
|
|
||||||
|
#define MSG_STATISTICS "Estadistica "
|
||||||
|
#define MSG_USB_PRINTING "Impresion de USB "
|
||||||
|
|
||||||
#endif // LANGUAGE_EN_H
|
#endif // LANGUAGE_EN_H
|
||||||
|
|
||||||
|
@ -8,7 +8,7 @@
|
|||||||
#ifndef LANGUAGE_IT_H
|
#ifndef LANGUAGE_IT_H
|
||||||
#define LANGUAGE_IT_H
|
#define LANGUAGE_IT_H
|
||||||
|
|
||||||
#define WELCOME_MSG MACHINE_NAME " pronto."
|
#define WELCOME_MSG CUSTOM_MENDEL_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"
|
||||||
@ -44,7 +44,6 @@
|
|||||||
#define MSG_BABYSTEP_Z "Babystep Z"
|
#define MSG_BABYSTEP_Z "Babystep Z"
|
||||||
#define MSG_ADJUSTZ "Auto regolare Z ?"
|
#define MSG_ADJUSTZ "Auto regolare Z ?"
|
||||||
#define MSG_PICK_Z "Vyberte vytisk"
|
#define MSG_PICK_Z "Vyberte vytisk"
|
||||||
#define MSG_HOMEYZ "Calibrate Z"
|
|
||||||
#define MSG_SETTINGS "Impostazioni"
|
#define MSG_SETTINGS "Impostazioni"
|
||||||
#define MSG_PREHEAT "Preriscalda"
|
#define MSG_PREHEAT "Preriscalda"
|
||||||
#define MSG_UNLOAD_FILAMENT "Scaricare fil."
|
#define MSG_UNLOAD_FILAMENT "Scaricare fil."
|
||||||
@ -107,7 +106,7 @@
|
|||||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||||
#define MSG_COUNT_X " Count X: "
|
#define MSG_COUNT_X " Count X: "
|
||||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||||
@ -237,4 +236,40 @@
|
|||||||
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
#define MSG_ENDSTOP_ABORT "Endstop abort"
|
||||||
#define MSG_RECTRACT "Rectract"
|
#define MSG_RECTRACT "Rectract"
|
||||||
|
|
||||||
|
#define MSG_HOMEYZ "Calibra Z"
|
||||||
|
#define MSG_HOMEYZ_PROGRESS "Calibrando Z"
|
||||||
|
#define MSG_HOMEYZ_DONE "Calibratura OK"
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_ERROR "Autotest negativo"
|
||||||
|
#define MSG_SELFTEST_PLEASECHECK "Verifica:"
|
||||||
|
#define MSG_SELFTEST_NOTCONNECTED "Non connesso"
|
||||||
|
#define MSG_SELFTEST_HEATERTHERMISTOR "Riscald./Termistore"
|
||||||
|
#define MSG_SELFTEST_BEDHEATER "Piastra/Riscaldatore"
|
||||||
|
#define MSG_SELFTEST_WIRINGERROR "Errore cablaggio"
|
||||||
|
#define MSG_SELFTEST_ENDSTOPS "Limiti corsa"
|
||||||
|
#define MSG_SELFTEST_MOTOR "Motore"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP "Limite corsa"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Lim. fuoriportata"
|
||||||
|
#define MSG_SELFTEST_OK "Autotest OK"
|
||||||
|
|
||||||
|
#define MSG_STATS_TOTALFILAMENT "Filamento tot:"
|
||||||
|
#define MSG_STATS_TOTALPRINTTIME "Tempo stampa tot:"
|
||||||
|
#define MSG_STATS_FILAMENTUSED "Filamento:"
|
||||||
|
#define MSG_STATS_PRINTTIME "Tempo stampa:"
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_START "Inizia autotest"
|
||||||
|
#define MSG_SELFTEST_CHECK_ENDSTOPS "Verifica limiti"
|
||||||
|
#define MSG_SELFTEST_CHECK_HOTEND "Verifica lim temp"
|
||||||
|
#define MSG_SELFTEST_CHECK_X "Verifica asse X"
|
||||||
|
#define MSG_SELFTEST_CHECK_Y "Verifica asse Y"
|
||||||
|
#define MSG_SELFTEST_CHECK_Z "Verifica asse Z"
|
||||||
|
#define MSG_SELFTEST_CHECK_BED "Verifica piastra"
|
||||||
|
#define MSG_SELFTEST_CHECK_ALLCORRECT "Nessun errore"
|
||||||
|
#define MSG_SELFTEST "Autotest"
|
||||||
|
#define MSG_SELFTEST_FAILED "Autotest fallito"
|
||||||
|
|
||||||
|
#define MSG_STATISTICS "Statistiche"
|
||||||
|
#define MSG_USB_PRINTING "Stampa da USB"
|
||||||
|
|
||||||
|
|
||||||
#endif // LANGUAGE_EN_H
|
#endif // LANGUAGE_EN_H
|
@ -8,7 +8,7 @@
|
|||||||
#ifndef LANGUAGE_PL_H
|
#ifndef LANGUAGE_PL_H
|
||||||
#define LANGUAGE_PL_H
|
#define LANGUAGE_PL_H
|
||||||
|
|
||||||
#define WELCOME_MSG MACHINE_NAME " gotowa"
|
#define WELCOME_MSG CUSTOM_MENDEL_NAME " gotowa"
|
||||||
#define MSG_SD_INSERTED "Karta wlozona"
|
#define MSG_SD_INSERTED "Karta wlozona"
|
||||||
#define MSG_SD_REMOVED "Karta wyjeta"
|
#define MSG_SD_REMOVED "Karta wyjeta"
|
||||||
#define MSG_MAIN "Menu glowne"
|
#define MSG_MAIN "Menu glowne"
|
||||||
@ -44,7 +44,6 @@
|
|||||||
#define MSG_BABYSTEP_Z "Dostrojenie osy Z"
|
#define MSG_BABYSTEP_Z "Dostrojenie osy Z"
|
||||||
#define MSG_ADJUSTZ "Autodostroic Z?"
|
#define MSG_ADJUSTZ "Autodostroic Z?"
|
||||||
#define MSG_PICK_Z "Vyberte vytisk"
|
#define MSG_PICK_Z "Vyberte vytisk"
|
||||||
#define MSG_HOMEYZ "Kalibrowac Z"
|
|
||||||
#define MSG_SETTINGS "Ustawienia"
|
#define MSG_SETTINGS "Ustawienia"
|
||||||
#define MSG_PREHEAT "Grzanie"
|
#define MSG_PREHEAT "Grzanie"
|
||||||
#define MSG_UNLOAD_FILAMENT "Wyjac filament"
|
#define MSG_UNLOAD_FILAMENT "Wyjac filament"
|
||||||
@ -107,7 +106,7 @@
|
|||||||
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
#define MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||||
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
#define MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||||
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
#define MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||||
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" MACHINE_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
#define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
|
||||||
#define MSG_COUNT_X " Count X: "
|
#define MSG_COUNT_X " Count X: "
|
||||||
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
#define MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||||
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||||
@ -254,4 +253,40 @@
|
|||||||
|
|
||||||
#define MSG_RECTRACT "Rectract"
|
#define MSG_RECTRACT "Rectract"
|
||||||
|
|
||||||
|
#define MSG_HOMEYZ "Kalibruj Z"
|
||||||
|
#define MSG_HOMEYZ_PROGRESS "Kalibruje Z"
|
||||||
|
#define MSG_HOMEYZ_DONE "Kalibracja OK"
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_ERROR "Selftest error !"
|
||||||
|
#define MSG_SELFTEST_PLEASECHECK "Skontroluj :"
|
||||||
|
#define MSG_SELFTEST_NOTCONNECTED "Nie podlaczono "
|
||||||
|
#define MSG_SELFTEST_HEATERTHERMISTOR "Heater/Thermistor"
|
||||||
|
#define MSG_SELFTEST_BEDHEATER "Bed / Heater"
|
||||||
|
#define MSG_SELFTEST_WIRINGERROR "Blad polaczenia"
|
||||||
|
#define MSG_SELFTEST_ENDSTOPS "Endstops"
|
||||||
|
#define MSG_SELFTEST_MOTOR "Silnik"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP "Endstop"
|
||||||
|
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||||
|
#define MSG_SELFTEST_OK "Self test OK"
|
||||||
|
|
||||||
|
#define MSG_STATS_TOTALFILAMENT "Filament lacznie :"
|
||||||
|
#define MSG_STATS_TOTALPRINTTIME "Czas calkowity :"
|
||||||
|
#define MSG_STATS_FILAMENTUSED "Filament : "
|
||||||
|
#define MSG_STATS_PRINTTIME "Czas druku : "
|
||||||
|
|
||||||
|
#define MSG_SELFTEST_START "Self test start "
|
||||||
|
#define MSG_SELFTEST_CHECK_ENDSTOPS "Kontrola endstops"
|
||||||
|
#define MSG_SELFTEST_CHECK_HOTEND "Kontrola hotend "
|
||||||
|
#define MSG_SELFTEST_CHECK_X "Kontrola X axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_Y "Kontrola Y axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_Z "Kontrola Z axis "
|
||||||
|
#define MSG_SELFTEST_CHECK_BED "Kontrola bed "
|
||||||
|
#define MSG_SELFTEST_CHECK_ALLCORRECT "Wszystko OK "
|
||||||
|
#define MSG_SELFTEST "Selftest "
|
||||||
|
#define MSG_SELFTEST_FAILED "Selftest nieudany"
|
||||||
|
|
||||||
|
#define MSG_STATISTICS "Statystyka "
|
||||||
|
#define MSG_USB_PRINTING "Druk z USB "
|
||||||
|
|
||||||
|
|
||||||
#endif // LANGUAGE_EN_H
|
#endif // LANGUAGE_EN_H
|
0
Firmware/mesh_bed_leveling.cpp
Executable file → Normal file
0
Firmware/mesh_bed_leveling.cpp
Executable file → Normal file
0
Firmware/mesh_bed_leveling.h
Executable file → Normal file
0
Firmware/mesh_bed_leveling.h
Executable file → Normal file
0
Firmware/motion_control.cpp
Executable file → Normal file
0
Firmware/motion_control.cpp
Executable file → Normal file
0
Firmware/motion_control.h
Executable file → Normal file
0
Firmware/motion_control.h
Executable file → Normal file
0
Firmware/pins.h
Executable file → Normal file
0
Firmware/pins.h
Executable file → Normal file
2
Firmware/planner.h
Executable file → Normal file
2
Firmware/planner.h
Executable file → Normal file
@ -132,7 +132,7 @@ extern block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for
|
|||||||
extern volatile unsigned char block_buffer_head; // Index of the next block to be pushed
|
extern volatile unsigned char block_buffer_head; // Index of the next block to be pushed
|
||||||
extern volatile unsigned char block_buffer_tail;
|
extern volatile unsigned char block_buffer_tail;
|
||||||
// Called when the current block is no longer needed. Discards the block and makes the memory
|
// Called when the current block is no longer needed. Discards the block and makes the memory
|
||||||
// availible for new blocks.
|
// available for new blocks.
|
||||||
FORCE_INLINE void plan_discard_current_block()
|
FORCE_INLINE void plan_discard_current_block()
|
||||||
{
|
{
|
||||||
if (block_buffer_head != block_buffer_tail) {
|
if (block_buffer_head != block_buffer_tail) {
|
||||||
|
0
Firmware/qr_solve.cpp
Executable file → Normal file
0
Firmware/qr_solve.cpp
Executable file → Normal file
0
Firmware/qr_solve.h
Executable file → Normal file
0
Firmware/qr_solve.h
Executable file → Normal file
0
Firmware/speed_lookuptable.h
Executable file → Normal file
0
Firmware/speed_lookuptable.h
Executable file → Normal file
@ -1083,8 +1083,7 @@ void finishAndDisableSteppers()
|
|||||||
void quickStop()
|
void quickStop()
|
||||||
{
|
{
|
||||||
DISABLE_STEPPER_DRIVER_INTERRUPT();
|
DISABLE_STEPPER_DRIVER_INTERRUPT();
|
||||||
while(blocks_queued())
|
while (blocks_queued()) plan_discard_current_block();
|
||||||
plan_discard_current_block();
|
|
||||||
current_block = NULL;
|
current_block = NULL;
|
||||||
ENABLE_STEPPER_DRIVER_INTERRUPT();
|
ENABLE_STEPPER_DRIVER_INTERRUPT();
|
||||||
}
|
}
|
||||||
|
0
Firmware/stepper.h
Executable file → Normal file
0
Firmware/stepper.h
Executable file → Normal file
209
Firmware/temperature.cpp
Executable file → Normal file
209
Firmware/temperature.cpp
Executable file → Normal file
@ -33,6 +33,7 @@
|
|||||||
#include "ultralcd.h"
|
#include "ultralcd.h"
|
||||||
#include "temperature.h"
|
#include "temperature.h"
|
||||||
#include "watchdog.h"
|
#include "watchdog.h"
|
||||||
|
#include "cardreader.h"
|
||||||
|
|
||||||
#include "Sd2PinMap.h"
|
#include "Sd2PinMap.h"
|
||||||
|
|
||||||
@ -438,12 +439,16 @@ void manage_heater()
|
|||||||
|
|
||||||
updateTemperaturesFromRawValues();
|
updateTemperaturesFromRawValues();
|
||||||
|
|
||||||
|
#ifdef TEMP_RUNAWAY_BED_HYSTERESIS
|
||||||
|
temp_runaway_check(0, target_temperature_bed, current_temperature_bed, (int)soft_pwm_bed, true);
|
||||||
|
#endif
|
||||||
|
|
||||||
for(int e = 0; e < EXTRUDERS; e++)
|
for(int e = 0; e < EXTRUDERS; e++)
|
||||||
{
|
{
|
||||||
|
|
||||||
#if defined (THERMAL_RUNAWAY_PROTECTION_PERIOD) && THERMAL_RUNAWAY_PROTECTION_PERIOD > 0
|
#ifdef TEMP_RUNAWAY_EXTRUDER_HYSTERESIS
|
||||||
thermal_runaway_protection(&thermal_runaway_state_machine[e], &thermal_runaway_timer[e], current_temperature[e], target_temperature[e], e, THERMAL_RUNAWAY_PROTECTION_PERIOD, THERMAL_RUNAWAY_PROTECTION_HYSTERESIS);
|
temp_runaway_check(e+1, target_temperature[e], current_temperature[e], (int)soft_pwm[e], false);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef PIDTEMP
|
#ifdef PIDTEMP
|
||||||
pid_input = current_temperature[e];
|
pid_input = current_temperature[e];
|
||||||
@ -562,10 +567,6 @@ void manage_heater()
|
|||||||
|
|
||||||
#if TEMP_SENSOR_BED != 0
|
#if TEMP_SENSOR_BED != 0
|
||||||
|
|
||||||
#ifdef THERMAL_RUNAWAY_PROTECTION_BED_PERIOD && THERMAL_RUNAWAY_PROTECTION_BED_PERIOD > 0
|
|
||||||
thermal_runaway_protection(&thermal_runaway_bed_state_machine, &thermal_runaway_bed_timer, current_temperature_bed, target_temperature_bed, 9, THERMAL_RUNAWAY_PROTECTION_BED_PERIOD, THERMAL_RUNAWAY_PROTECTION_BED_HYSTERESIS);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef PIDTEMPBED
|
#ifdef PIDTEMPBED
|
||||||
pid_input = current_temperature_bed;
|
pid_input = current_temperature_bed;
|
||||||
|
|
||||||
@ -735,6 +736,31 @@ static float analog2tempBed(int raw) {
|
|||||||
// Overflow: Set to last value in the table
|
// Overflow: Set to last value in the table
|
||||||
if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]);
|
if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]);
|
||||||
|
|
||||||
|
|
||||||
|
// temperature offset adjustment
|
||||||
|
#ifdef BED_OFFSET
|
||||||
|
float _offset = BED_OFFSET;
|
||||||
|
float _offset_center = BED_OFFSET_CENTER;
|
||||||
|
float _offset_start = BED_OFFSET_START;
|
||||||
|
float _first_koef = (_offset / 2) / (_offset_center - _offset_start);
|
||||||
|
float _second_koef = (_offset / 2) / (100 - _offset_center);
|
||||||
|
|
||||||
|
|
||||||
|
if (celsius >= _offset_start && celsius <= _offset_center)
|
||||||
|
{
|
||||||
|
celsius = celsius + (_first_koef * (celsius - _offset_start));
|
||||||
|
}
|
||||||
|
else if (celsius > _offset_center && celsius <= 100)
|
||||||
|
{
|
||||||
|
celsius = celsius + (_first_koef * (_offset_center - _offset_start)) + ( _second_koef * ( celsius - ( 100 - _offset_center ) )) ;
|
||||||
|
}
|
||||||
|
else if (celsius > 100)
|
||||||
|
{
|
||||||
|
celsius = celsius + _offset;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
return celsius;
|
return celsius;
|
||||||
#elif defined BED_USES_AD595
|
#elif defined BED_USES_AD595
|
||||||
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
|
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
|
||||||
@ -751,7 +777,9 @@ static void updateTemperaturesFromRawValues()
|
|||||||
{
|
{
|
||||||
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
|
||||||
}
|
}
|
||||||
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
|
||||||
|
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
||||||
|
|
||||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||||
redundant_temperature = analog2temp(redundant_temperature_raw, 1);
|
redundant_temperature = analog2temp(redundant_temperature_raw, 1);
|
||||||
#endif
|
#endif
|
||||||
@ -1013,67 +1041,116 @@ void setWatch()
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#if (defined (THERMAL_RUNAWAY_PROTECTION_PERIOD) && THERMAL_RUNAWAY_PROTECTION_PERIOD > 0) || (defined (THERMAL_RUNAWAY_PROTECTION_BED_PERIOD) && THERMAL_RUNAWAY_PROTECTION_BED_PERIOD > 0)
|
#if (defined (TEMP_RUNAWAY_BED_HYSTERESIS) && TEMP_RUNAWAY_BED_TIMEOUT > 0) || (defined (TEMP_RUNAWAY_EXTRUDER_HYSTERESIS) && TEMP_RUNAWAY_EXTRUDER_TIMEOUT > 0)
|
||||||
void thermal_runaway_protection(int *state, unsigned long *timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc)
|
void temp_runaway_check(int _heater_id, float _target_temperature, float _current_temperature, float _output, bool _isbed)
|
||||||
{
|
{
|
||||||
/*
|
float __hysteresis = 0;
|
||||||
SERIAL_ECHO_START;
|
int __timeout = 0;
|
||||||
SERIAL_ECHO("Thermal Thermal Runaway Running. Heater ID:");
|
bool temp_runaway_check_active = false;
|
||||||
SERIAL_ECHO(heater_id);
|
|
||||||
SERIAL_ECHO(" ; State:");
|
_heater_id = (_isbed) ? _heater_id++ : _heater_id;
|
||||||
SERIAL_ECHO(*state);
|
|
||||||
SERIAL_ECHO(" ; Timer:");
|
#ifdef TEMP_RUNAWAY_BED_TIMEOUT
|
||||||
SERIAL_ECHO(*timer);
|
if (_isbed)
|
||||||
SERIAL_ECHO(" ; Temperature:");
|
{
|
||||||
SERIAL_ECHO(temperature);
|
__hysteresis = TEMP_RUNAWAY_BED_HYSTERESIS;
|
||||||
SERIAL_ECHO(" ; Target Temp:");
|
__timeout = TEMP_RUNAWAY_BED_TIMEOUT;
|
||||||
SERIAL_ECHO(target_temperature);
|
}
|
||||||
SERIAL_ECHOLN("");
|
#endif
|
||||||
*/
|
#ifdef TEMP_RUNAWAY_EXTRUDER_TIMEOUT
|
||||||
if ((target_temperature == 0) || thermal_runaway)
|
if (!_isbed)
|
||||||
{
|
{
|
||||||
*state = 0;
|
__hysteresis = TEMP_RUNAWAY_EXTRUDER_HYSTERESIS;
|
||||||
*timer = 0;
|
__timeout = TEMP_RUNAWAY_EXTRUDER_TIMEOUT;
|
||||||
return;
|
}
|
||||||
}
|
#endif
|
||||||
switch (*state)
|
|
||||||
{
|
if (millis() - temp_runaway_timer[_heater_id] > 2000)
|
||||||
case 0: // "Heater Inactive" state
|
{
|
||||||
if (target_temperature > 0) *state = 1;
|
temp_runaway_timer[_heater_id] = millis();
|
||||||
break;
|
|
||||||
case 1: // "First Heating" state
|
if (_output == 0)
|
||||||
if (temperature >= target_temperature) *state = 2;
|
{
|
||||||
break;
|
temp_runaway_check_active = false;
|
||||||
case 2: // "Temperature Stable" state
|
temp_runaway_error_counter[_heater_id] = 0;
|
||||||
if (temperature >= (target_temperature - hysteresis_degc))
|
}
|
||||||
{
|
|
||||||
*timer = millis();
|
if (temp_runaway_target[_heater_id] != _target_temperature)
|
||||||
}
|
{
|
||||||
else if ( (millis() - *timer) > ((unsigned long) period_seconds) * 1000)
|
if (_target_temperature > 0)
|
||||||
{
|
{
|
||||||
SERIAL_ERROR_START;
|
temp_runaway_status[_heater_id] = 1;
|
||||||
SERIAL_ERRORLNPGM("Thermal Runaway, system stopped! Heater_ID: ");
|
temp_runaway_target[_heater_id] = _target_temperature;
|
||||||
SERIAL_ERRORLN((int)heater_id);
|
}
|
||||||
LCD_ALERTMESSAGEPGM("THERMAL RUNAWAY");
|
else
|
||||||
thermal_runaway = true;
|
{
|
||||||
while(1)
|
temp_runaway_status[_heater_id] = 0;
|
||||||
{
|
temp_runaway_target[_heater_id] = _target_temperature;
|
||||||
disable_heater();
|
}
|
||||||
disable_x();
|
}
|
||||||
disable_y();
|
|
||||||
disable_z();
|
if (_current_temperature >= _target_temperature && temp_runaway_status[_heater_id] == 1)
|
||||||
disable_e0();
|
{
|
||||||
disable_e1();
|
temp_runaway_status[_heater_id] = 2;
|
||||||
disable_e2();
|
temp_runaway_check_active = false;
|
||||||
manage_heater();
|
}
|
||||||
lcd_update();
|
|
||||||
}
|
if (!temp_runaway_check_active && _output > 0)
|
||||||
}
|
{
|
||||||
break;
|
temp_runaway_check_active = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (temp_runaway_check_active)
|
||||||
|
{
|
||||||
|
// we are in range
|
||||||
|
if (_target_temperature - __hysteresis < _current_temperature && _current_temperature < _target_temperature + __hysteresis)
|
||||||
|
{
|
||||||
|
temp_runaway_check_active = false;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (temp_runaway_status[_heater_id] > 1)
|
||||||
|
{
|
||||||
|
temp_runaway_error_counter[_heater_id]++;
|
||||||
|
|
||||||
|
if (temp_runaway_error_counter[_heater_id] * 2 > __timeout)
|
||||||
|
{
|
||||||
|
temp_runaway_stop();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void temp_runaway_stop()
|
||||||
|
{
|
||||||
|
cancel_heatup = true;
|
||||||
|
quickStop();
|
||||||
|
if (card.sdprinting)
|
||||||
|
{
|
||||||
|
card.sdprinting = false;
|
||||||
|
card.closefile();
|
||||||
|
}
|
||||||
|
LCD_ALERTMESSAGEPGM("THERMAL RUNAWAY");
|
||||||
|
disable_heater();
|
||||||
|
disable_x();
|
||||||
|
disable_y();
|
||||||
|
disable_e0();
|
||||||
|
disable_e1();
|
||||||
|
disable_e2();
|
||||||
|
manage_heater();
|
||||||
|
lcd_update();
|
||||||
|
WRITE(BEEPER, HIGH);
|
||||||
|
delayMicroseconds(500);
|
||||||
|
WRITE(BEEPER, LOW);
|
||||||
|
delayMicroseconds(100);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
void disable_heater()
|
void disable_heater()
|
||||||
{
|
{
|
||||||
for(int i=0;i<EXTRUDERS;i++)
|
for(int i=0;i<EXTRUDERS;i++)
|
||||||
@ -1144,7 +1221,7 @@ void bed_max_temp_error(void) {
|
|||||||
#endif
|
#endif
|
||||||
if(IsStopped() == false) {
|
if(IsStopped() == false) {
|
||||||
SERIAL_ERROR_START;
|
SERIAL_ERROR_START;
|
||||||
SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
|
SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !");
|
||||||
LCD_ALERTMESSAGEPGM("Err: MAXTEMP BED");
|
LCD_ALERTMESSAGEPGM("Err: MAXTEMP BED");
|
||||||
}
|
}
|
||||||
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
||||||
|
18
Firmware/temperature.h
Executable file → Normal file
18
Firmware/temperature.h
Executable file → Normal file
@ -155,23 +155,21 @@ FORCE_INLINE bool isCoolingBed() {
|
|||||||
#error Invalid number of extruders
|
#error Invalid number of extruders
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if (defined (TEMP_RUNAWAY_BED_HYSTERESIS) && TEMP_RUNAWAY_BED_TIMEOUT > 0) || (defined (TEMP_RUNAWAY_EXTRUDER_HYSTERESIS) && TEMP_RUNAWAY_EXTRUDER_TIMEOUT > 0)
|
||||||
|
static float temp_runaway_status[4];
|
||||||
|
static float temp_runaway_target[4];
|
||||||
|
static float temp_runaway_timer[4];
|
||||||
|
static int temp_runaway_error_counter[4];
|
||||||
|
|
||||||
|
void temp_runaway_check(int _heater_id, float _target_temperature, float _current_temperature, float _output, bool _isbed);
|
||||||
|
void temp_runaway_stop();
|
||||||
|
#endif
|
||||||
|
|
||||||
int getHeaterPower(int heater);
|
int getHeaterPower(int heater);
|
||||||
void disable_heater();
|
void disable_heater();
|
||||||
void setWatch();
|
void setWatch();
|
||||||
void updatePID();
|
void updatePID();
|
||||||
|
|
||||||
#if (defined (THERMAL_RUNAWAY_PROTECTION_PERIOD) && THERMAL_RUNAWAY_PROTECTION_PERIOD > 0) || (defined (THERMAL_RUNAWAY_PROTECTION_BED_PERIOD) && THERMAL_RUNAWAY_PROTECTION_BED_PERIOD > 0)
|
|
||||||
void thermal_runaway_protection(int *state, unsigned long *timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc);
|
|
||||||
static int thermal_runaway_state_machine[3]; // = {0,0,0};
|
|
||||||
static unsigned long thermal_runaway_timer[3]; // = {0,0,0};
|
|
||||||
static bool thermal_runaway = false;
|
|
||||||
#if TEMP_SENSOR_BED != 0
|
|
||||||
static int thermal_runaway_bed_state_machine;
|
|
||||||
static unsigned long thermal_runaway_bed_timer;
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
FORCE_INLINE void autotempShutdown(){
|
FORCE_INLINE void autotempShutdown(){
|
||||||
#ifdef AUTOTEMP
|
#ifdef AUTOTEMP
|
||||||
|
0
Firmware/thermistortables.h
Executable file → Normal file
0
Firmware/thermistortables.h
Executable file → Normal file
File diff suppressed because it is too large
Load Diff
@ -22,9 +22,20 @@
|
|||||||
void lcd_change_success();
|
void lcd_change_success();
|
||||||
void lcd_loading_color();
|
void lcd_loading_color();
|
||||||
void lcd_force_language_selection();
|
void lcd_force_language_selection();
|
||||||
|
void lcd_sdcard_stop();
|
||||||
|
void lcd_calibration();
|
||||||
|
|
||||||
bool lcd_detected(void);
|
bool lcd_detected(void);
|
||||||
|
|
||||||
|
static void lcd_selftest();
|
||||||
|
static bool lcd_selfcheck_endstops();
|
||||||
|
static bool lcd_selfcheck_axis(int _axis, int _travel);
|
||||||
|
static bool lcd_selfcheck_check_heater(bool _isbed);
|
||||||
|
static int lcd_selftest_screen(int _step, int _progress, int _progress_scale, bool _clear, int _delay);
|
||||||
|
static void lcd_selftest_screen_step(int _row, int _col, int _state, const char *_name, const char *_indicator);
|
||||||
|
static void lcd_selftest_error(int _error_no, const char *_error_1, const char *_error_2);
|
||||||
|
static void lcd_menu_statistics();
|
||||||
|
|
||||||
#ifdef DOGLCD
|
#ifdef DOGLCD
|
||||||
extern int lcd_contrast;
|
extern int lcd_contrast;
|
||||||
void lcd_setcontrast(uint8_t value);
|
void lcd_setcontrast(uint8_t value);
|
||||||
@ -68,6 +79,7 @@
|
|||||||
bool lcd_clicked();
|
bool lcd_clicked();
|
||||||
|
|
||||||
void lcd_ignore_click(bool b=true);
|
void lcd_ignore_click(bool b=true);
|
||||||
|
void lcd_commands();
|
||||||
|
|
||||||
#ifdef NEWPANEL
|
#ifdef NEWPANEL
|
||||||
#define EN_C (1<<BLEN_C)
|
#define EN_C (1<<BLEN_C)
|
||||||
@ -109,7 +121,8 @@
|
|||||||
#endif//NEWPANEL
|
#endif//NEWPANEL
|
||||||
|
|
||||||
#else //no LCD
|
#else //no LCD
|
||||||
FORCE_INLINE void lcd_update() {}
|
FORCE_INLINE void
|
||||||
|
{}
|
||||||
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) {}
|
||||||
FORCE_INLINE void lcd_buttons_update() {}
|
FORCE_INLINE void lcd_buttons_update() {}
|
||||||
@ -132,6 +145,7 @@ char *ftostr3(const float &x);
|
|||||||
char *ftostr31ns(const float &x); // float to string without sign character
|
char *ftostr31ns(const float &x); // float to string without sign character
|
||||||
char *ftostr31(const float &x);
|
char *ftostr31(const float &x);
|
||||||
char *ftostr32(const float &x);
|
char *ftostr32(const float &x);
|
||||||
|
char *ftostr32ns(const float &x);
|
||||||
char *ftostr43(const float &x);
|
char *ftostr43(const float &x);
|
||||||
char *ftostr12ns(const float &x);
|
char *ftostr12ns(const float &x);
|
||||||
char *ftostr13ns(const float &x);
|
char *ftostr13ns(const float &x);
|
||||||
|
@ -6,7 +6,7 @@ int scrollstuff = 0;
|
|||||||
char longFilenameOLD[LONG_FILENAME_LENGTH];
|
char longFilenameOLD[LONG_FILENAME_LENGTH];
|
||||||
|
|
||||||
#include "Configuration_prusa.h"
|
#include "Configuration_prusa.h"
|
||||||
|
#include "Marlin.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 Russian 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.
|
||||||
@ -628,15 +628,35 @@ static void lcd_implementation_status_screen()
|
|||||||
lcd.print('%');
|
lcd.print('%');
|
||||||
lcd.print(" ");
|
lcd.print(" ");
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//Print SD status
|
//Print SD status
|
||||||
lcd.setCursor(0, 2);
|
lcd.setCursor(0, 2);
|
||||||
lcd_printPGM(PSTR("SD"));
|
if (is_usb_printing)
|
||||||
|
{
|
||||||
if (IS_SD_PRINTING)
|
lcd_printPGM(PSTR("--"));
|
||||||
lcd.print(itostr3(card.percentDone()));
|
}
|
||||||
else
|
else
|
||||||
lcd_printPGM(PSTR("---"));
|
{
|
||||||
lcd.print('%');
|
lcd_printPGM(PSTR("SD"));
|
||||||
|
}
|
||||||
|
if (IS_SD_PRINTING)
|
||||||
|
{
|
||||||
|
lcd.print(itostr3(card.percentDone()));
|
||||||
|
lcd.print('%');
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (is_usb_printing)
|
||||||
|
{
|
||||||
|
lcd_printPGM(PSTR(">USB"));
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
lcd_printPGM(PSTR("---"));
|
||||||
|
lcd.print('%');
|
||||||
|
}
|
||||||
|
}
|
||||||
lcd.print(" ");
|
lcd.print(" ");
|
||||||
|
|
||||||
//Print time elapsed
|
//Print time elapsed
|
||||||
@ -658,27 +678,36 @@ static void lcd_implementation_status_screen()
|
|||||||
//Print status line
|
//Print status line
|
||||||
lcd.setCursor(0, 3);
|
lcd.setCursor(0, 3);
|
||||||
|
|
||||||
if(strcmp(lcd_status_message, "SD-PRINTING ") == 0){
|
if (heating_status != 0) { custom_message = true; }
|
||||||
|
|
||||||
if(strcmp(longFilenameOLD, card.longFilename) != 0){
|
if ((IS_SD_PRINTING) && !custom_message)
|
||||||
|
{
|
||||||
|
|
||||||
|
if(strcmp(longFilenameOLD, card.longFilename) != 0)
|
||||||
|
{
|
||||||
memset(longFilenameOLD,'\0',strlen(longFilenameOLD));
|
memset(longFilenameOLD,'\0',strlen(longFilenameOLD));
|
||||||
sprintf(longFilenameOLD, "%s", card.longFilename);
|
sprintf(longFilenameOLD, "%s", card.longFilename);
|
||||||
scrollstuff = 0;
|
scrollstuff = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(strlen(card.longFilename) > LCD_WIDTH){
|
if(strlen(card.longFilename) > LCD_WIDTH)
|
||||||
|
{
|
||||||
|
|
||||||
int inters = 0;
|
int inters = 0;
|
||||||
int gh = scrollstuff;
|
int gh = scrollstuff;
|
||||||
while( ((gh-scrollstuff)<LCD_WIDTH) && (inters == 0) ){
|
while( ((gh-scrollstuff)<LCD_WIDTH) && (inters == 0) )
|
||||||
|
{
|
||||||
|
|
||||||
if(card.longFilename[gh] == '\0'){
|
if(card.longFilename[gh] == '\0')
|
||||||
|
{
|
||||||
lcd.setCursor(gh-scrollstuff, 3);
|
lcd.setCursor(gh-scrollstuff, 3);
|
||||||
lcd.print(card.longFilename[gh-1]);
|
lcd.print(card.longFilename[gh-1]);
|
||||||
scrollstuff = 0;
|
scrollstuff = 0;
|
||||||
gh = scrollstuff;
|
gh = scrollstuff;
|
||||||
inters = 1;
|
inters = 1;
|
||||||
|
}
|
||||||
}else{
|
else
|
||||||
|
{
|
||||||
lcd.setCursor(gh-scrollstuff, 3);
|
lcd.setCursor(gh-scrollstuff, 3);
|
||||||
lcd.print(card.longFilename[gh-1]);
|
lcd.print(card.longFilename[gh-1]);
|
||||||
gh++;
|
gh++;
|
||||||
@ -687,30 +716,129 @@ static void lcd_implementation_status_screen()
|
|||||||
|
|
||||||
}
|
}
|
||||||
scrollstuff++;
|
scrollstuff++;
|
||||||
|
}
|
||||||
}else{
|
else
|
||||||
|
{
|
||||||
lcd.print(longFilenameOLD);
|
lcd.print(longFilenameOLD);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
}else{
|
|
||||||
|
|
||||||
lcd.print(lcd_status_message);
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (custom_message)
|
||||||
|
{
|
||||||
|
if (heating_status != 0)
|
||||||
|
{
|
||||||
|
heating_status_counter++;
|
||||||
|
if (heating_status_counter > 13)
|
||||||
|
{
|
||||||
|
heating_status_counter = 0;
|
||||||
|
}
|
||||||
|
lcd.setCursor(7, 3);
|
||||||
|
lcd_printPGM(PSTR(" "));
|
||||||
|
|
||||||
for(int fillspace = 0; fillspace<20;fillspace++){
|
for (int dots = 0; dots < heating_status_counter; dots++)
|
||||||
if((lcd_status_message[fillspace] > 31 )){
|
{
|
||||||
|
lcd.setCursor(7 + dots, 3);
|
||||||
|
lcd_printPGM(PSTR("."));
|
||||||
|
}
|
||||||
|
|
||||||
}else{
|
switch (heating_status)
|
||||||
|
{
|
||||||
|
case 1:
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd_printPGM(MSG_HEATING);
|
||||||
|
break;
|
||||||
|
case 2:
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd_printPGM(MSG_HEATING_COMPLETE);
|
||||||
|
heating_status = 0;
|
||||||
|
heating_status_counter = 0;
|
||||||
|
custom_message = false;
|
||||||
|
break;
|
||||||
|
case 3:
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd_printPGM(MSG_BED_HEATING);
|
||||||
|
break;
|
||||||
|
case 4:
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd_printPGM(MSG_BED_DONE);
|
||||||
|
heating_status = 0;
|
||||||
|
heating_status_counter = 0;
|
||||||
|
custom_message = false;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (custom_message_type == 1) //// Z calibration G80 mesh bed leveling
|
||||||
|
{
|
||||||
|
if (custom_message_state > 10)
|
||||||
|
{
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd.print(" ");
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd_printPGM(MSG_HOMEYZ_PROGRESS);
|
||||||
|
lcd.print(" : ");
|
||||||
|
lcd.print(custom_message_state-10);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if (custom_message_state == 3)
|
||||||
|
{
|
||||||
|
lcd_printPGM(WELCOME_MSG);
|
||||||
|
lcd_setstatuspgm(WELCOME_MSG);
|
||||||
|
custom_message = false;
|
||||||
|
custom_message_type = 0;
|
||||||
|
}
|
||||||
|
if (custom_message_state > 3 && custom_message_state < 10 )
|
||||||
|
{
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd.print(" ");
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd_printPGM(MSG_HOMEYZ_DONE);
|
||||||
|
custom_message_state--;
|
||||||
|
}
|
||||||
|
if (custom_message_state == 10)
|
||||||
|
{
|
||||||
|
lcd_printPGM(MSG_HOMEYZ_DONE);
|
||||||
|
custom_message_state = 9;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
if (custom_message_type == 2) //// load filament
|
||||||
|
{
|
||||||
|
lcd.print(lcd_status_message);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
lcd.print(lcd_status_message);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for(int fillspace = 0; fillspace<20;fillspace++)
|
||||||
|
{
|
||||||
|
if((lcd_status_message[fillspace] > 31 ))
|
||||||
|
{
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
lcd.print(' ');
|
lcd.print(' ');
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (is_usb_printing==1 && custom_message==0)
|
||||||
|
{
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd.print(" ");
|
||||||
|
lcd.setCursor(0, 3);
|
||||||
|
lcd_printPGM(MSG_USB_PRINTING);
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
0
Firmware/ultralcd_st7920_u8glib_rrd.h
Executable file → Normal file
0
Firmware/ultralcd_st7920_u8glib_rrd.h
Executable file → Normal file
17
Firmware/variants/1_75mm-RAMBo10a-E3Dv6full.h
Executable file → Normal file
17
Firmware/variants/1_75mm-RAMBo10a-E3Dv6full.h
Executable file → Normal file
@ -41,6 +41,10 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define Z_MAX_POS 201
|
#define Z_MAX_POS 201
|
||||||
#define Z_MIN_POS 0.23
|
#define Z_MIN_POS 0.23
|
||||||
|
|
||||||
|
// Canceled home position
|
||||||
|
#define X_CANCEL_POS 50
|
||||||
|
#define Y_CANCEL_POS 180
|
||||||
|
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
@ -179,6 +183,19 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||||
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
|
// temperature runaway
|
||||||
|
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||||
|
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||||
|
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||||
|
|
||||||
|
|
||||||
/*------------------------------------
|
/*------------------------------------
|
||||||
THERMISTORS SETTINGS
|
THERMISTORS SETTINGS
|
||||||
|
16
Firmware/variants/1_75mm-RAMBo10a-E3Dv6lite.h
Executable file → Normal file
16
Firmware/variants/1_75mm-RAMBo10a-E3Dv6lite.h
Executable file → Normal file
@ -41,6 +41,10 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define Z_MAX_POS 201
|
#define Z_MAX_POS 201
|
||||||
#define Z_MIN_POS 0.23
|
#define Z_MIN_POS 0.23
|
||||||
|
|
||||||
|
// Canceled home position
|
||||||
|
#define X_CANCEL_POS 50
|
||||||
|
#define Y_CANCEL_POS 180
|
||||||
|
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
@ -179,6 +183,18 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||||
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
|
// temperature runaway
|
||||||
|
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||||
|
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||||
|
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||||
|
|
||||||
/*------------------------------------
|
/*------------------------------------
|
||||||
THERMISTORS SETTINGS
|
THERMISTORS SETTINGS
|
||||||
|
16
Firmware/variants/1_75mm-RAMBo13a-E3Dv6full.h
Executable file → Normal file
16
Firmware/variants/1_75mm-RAMBo13a-E3Dv6full.h
Executable file → Normal file
@ -41,6 +41,10 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define Z_MAX_POS 201
|
#define Z_MAX_POS 201
|
||||||
#define Z_MIN_POS 0.23
|
#define Z_MIN_POS 0.23
|
||||||
|
|
||||||
|
// Canceled home position
|
||||||
|
#define X_CANCEL_POS 50
|
||||||
|
#define Y_CANCEL_POS 180
|
||||||
|
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
@ -179,6 +183,18 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||||
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
|
// temperature runaway
|
||||||
|
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||||
|
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||||
|
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||||
|
|
||||||
/*------------------------------------
|
/*------------------------------------
|
||||||
THERMISTORS SETTINGS
|
THERMISTORS SETTINGS
|
||||||
|
16
Firmware/variants/1_75mm-RAMBo13a-E3Dv6lite.h
Executable file → Normal file
16
Firmware/variants/1_75mm-RAMBo13a-E3Dv6lite.h
Executable file → Normal file
@ -41,6 +41,10 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define Z_MAX_POS 201
|
#define Z_MAX_POS 201
|
||||||
#define Z_MIN_POS 0.23
|
#define Z_MIN_POS 0.23
|
||||||
|
|
||||||
|
// Canceled home position
|
||||||
|
#define X_CANCEL_POS 50
|
||||||
|
#define Y_CANCEL_POS 180
|
||||||
|
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
@ -179,6 +183,18 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||||
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
|
// temperature runaway
|
||||||
|
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||||
|
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||||
|
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||||
|
|
||||||
/*------------------------------------
|
/*------------------------------------
|
||||||
THERMISTORS SETTINGS
|
THERMISTORS SETTINGS
|
||||||
|
@ -1,299 +0,0 @@
|
|||||||
#ifndef CONFIGURATION_PRUSA_H
|
|
||||||
#define CONFIGURATION_PRUSA_H
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
GENERAL SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Printer revision
|
|
||||||
#define FILAMENT_SIZE "1_7dev"
|
|
||||||
#define NOZZLE_TYPE "E3Dv6lite"
|
|
||||||
|
|
||||||
// Developer flag
|
|
||||||
#define DEVELOPER
|
|
||||||
|
|
||||||
// Printer name
|
|
||||||
#define CUSTOM_MENDEL_NAME "Prusa i3 dev"
|
|
||||||
|
|
||||||
// Electronics
|
|
||||||
#define MOTHERBOARD BOARD_RAMBO_MINI_1_3
|
|
||||||
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
AXIS SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Steps per unit {X,Y,Z,E}
|
|
||||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,161.3}
|
|
||||||
|
|
||||||
// Endstop inverting
|
|
||||||
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
|
||||||
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
|
||||||
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
|
|
||||||
|
|
||||||
// Home position
|
|
||||||
#define MANUAL_X_HOME_POS 0
|
|
||||||
#define MANUAL_Y_HOME_POS -2.2
|
|
||||||
#define MANUAL_Z_HOME_POS 0.2
|
|
||||||
|
|
||||||
// Travel limits after homing
|
|
||||||
#define X_MAX_POS 255
|
|
||||||
#define X_MIN_POS 0
|
|
||||||
#define Y_MAX_POS 210
|
|
||||||
#define Y_MIN_POS -4
|
|
||||||
#define Z_MAX_POS 210
|
|
||||||
#define Z_MIN_POS 0.2
|
|
||||||
|
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
|
||||||
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min)
|
|
||||||
|
|
||||||
#define DEFAULT_MAX_FEEDRATE {500, 500, 1000, 25} // (mm/sec)
|
|
||||||
#define DEFAULT_MAX_ACCELERATION {9000,9000,1000,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_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
|
|
||||||
|
|
||||||
|
|
||||||
#define MANUAL_FEEDRATE {3000, 3000, 1000, 100} // set the speeds for manual moves (mm/min)
|
|
||||||
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
EXTRUDER SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Mintemps
|
|
||||||
#define HEATER_0_MINTEMP 15
|
|
||||||
#define HEATER_1_MINTEMP 5
|
|
||||||
#define HEATER_2_MINTEMP 5
|
|
||||||
#define BED_MINTEMP 15
|
|
||||||
|
|
||||||
// Maxtemps
|
|
||||||
#define HEATER_0_MAXTEMP 265
|
|
||||||
#define HEATER_1_MAXTEMP 265
|
|
||||||
#define HEATER_2_MAXTEMP 265
|
|
||||||
#define BED_MAXTEMP 150
|
|
||||||
|
|
||||||
// Define PID constants for extruder
|
|
||||||
#define DEFAULT_Kp 40.925
|
|
||||||
#define DEFAULT_Ki 4.875
|
|
||||||
#define DEFAULT_Kd 86.085
|
|
||||||
|
|
||||||
// Extrude mintemp
|
|
||||||
#define EXTRUDE_MINTEMP 130
|
|
||||||
|
|
||||||
// Extruder cooling fans
|
|
||||||
#define EXTRUDER_0_AUTO_FAN_PIN 8
|
|
||||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
|
||||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
|
||||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
|
||||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
LOAD/UNLOAD FILAMENT SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Load filament commands
|
|
||||||
#define LOAD_FILAMENT_0 "M83"
|
|
||||||
#define LOAD_FILAMENT_1 "G1 E70 F400"
|
|
||||||
#define LOAD_FILAMENT_2 "G1 E40 F100"
|
|
||||||
|
|
||||||
// Unload filament commands
|
|
||||||
#define UNLOAD_FILAMENT_0 "M83"
|
|
||||||
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
CHANGE FILAMENT SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Filament change configuration
|
|
||||||
#define FILAMENTCHANGEENABLE
|
|
||||||
#ifdef FILAMENTCHANGEENABLE
|
|
||||||
#define FILAMENTCHANGE_XPOS 211
|
|
||||||
#define FILAMENTCHANGE_YPOS 0
|
|
||||||
#define FILAMENTCHANGE_ZADD 2
|
|
||||||
#define FILAMENTCHANGE_FIRSTRETRACT -2
|
|
||||||
#define FILAMENTCHANGE_FINALRETRACT -80
|
|
||||||
|
|
||||||
#define FILAMENTCHANGE_FIRSTFEED 70
|
|
||||||
#define FILAMENTCHANGE_FINALFEED 50
|
|
||||||
#define FILAMENTCHANGE_RECFEED 5
|
|
||||||
|
|
||||||
#define FILAMENTCHANGE_XYFEED 70
|
|
||||||
#define FILAMENTCHANGE_EFEED 20
|
|
||||||
#define FILAMENTCHANGE_RFEED 400
|
|
||||||
#define FILAMENTCHANGE_EXFEED 2
|
|
||||||
#define FILAMENTCHANGE_ZFEED 300
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
ADDITIONAL FEATURES SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Define Prusa filament runout sensor
|
|
||||||
//#define FILAMENT_RUNOUT_SUPPORT
|
|
||||||
|
|
||||||
#ifdef FILAMENT_RUNOUT_SUPPORT
|
|
||||||
#define FILAMENT_RUNOUT_SENSOR 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
MOTOR CURRENT SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Motor Current setting for BIG RAMBo
|
|
||||||
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
|
|
||||||
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
|
|
||||||
|
|
||||||
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
|
|
||||||
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
|
|
||||||
#define MOTOR_CURRENT_PWM_RANGE 2000
|
|
||||||
#define DEFAULT_PWM_MOTOR_CURRENT {270, 450, 450} // {XY,Z,E}
|
|
||||||
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 830, 500} // {XY,Z,E}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
BED SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
// Define Mesh Bed Leveling system to enable it
|
|
||||||
#define MESH_BED_LEVELING
|
|
||||||
#ifdef MESH_BED_LEVELING
|
|
||||||
|
|
||||||
#define MBL_Z_STEP 0.01
|
|
||||||
|
|
||||||
// Mesh definitions
|
|
||||||
#define MESH_MIN_X 35
|
|
||||||
#define MESH_MAX_X 239
|
|
||||||
#define MESH_MIN_Y 6
|
|
||||||
#define MESH_MAX_Y 202
|
|
||||||
|
|
||||||
// Mesh upsample definition
|
|
||||||
#define MESH_NUM_X_POINTS 7
|
|
||||||
#define MESH_NUM_Y_POINTS 7
|
|
||||||
// Mesh measure definition
|
|
||||||
#define MESH_MEAS_NUM_X_POINTS 3
|
|
||||||
#define MESH_MEAS_NUM_Y_POINTS 3
|
|
||||||
|
|
||||||
#define MESH_HOME_Z_CALIB 0.2
|
|
||||||
#define MESH_HOME_Z_SEARCH 5
|
|
||||||
|
|
||||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
|
||||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
|
||||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Bed Temperature Control
|
|
||||||
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
|
|
||||||
//
|
|
||||||
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
|
|
||||||
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
|
|
||||||
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
|
|
||||||
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
|
|
||||||
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
|
|
||||||
// shouldn't use bed PID until someone else verifies your hardware works.
|
|
||||||
// If this is enabled, find your own PID constants below.
|
|
||||||
#define PIDTEMPBED
|
|
||||||
//
|
|
||||||
//#define BED_LIMIT_SWITCHING
|
|
||||||
|
|
||||||
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
|
||||||
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
|
||||||
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
|
||||||
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
|
||||||
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
|
||||||
|
|
||||||
#ifdef PIDTEMPBED
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
|
||||||
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
|
|
||||||
#define DEFAULT_bedKp 126.13
|
|
||||||
#define DEFAULT_bedKi 4.30
|
|
||||||
#define DEFAULT_bedKd 924.76
|
|
||||||
|
|
||||||
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
|
|
||||||
//from pidautotune
|
|
||||||
// #define DEFAULT_bedKp 97.1
|
|
||||||
// #define DEFAULT_bedKi 1.41
|
|
||||||
// #define DEFAULT_bedKd 1675.16
|
|
||||||
|
|
||||||
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
|
|
||||||
#endif // PIDTEMPBED
|
|
||||||
|
|
||||||
|
|
||||||
/*-----------------------------------
|
|
||||||
PREHEAT SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
#define PLA_PREHEAT_HOTEND_TEMP 210
|
|
||||||
#define PLA_PREHEAT_HPB_TEMP 50
|
|
||||||
#define PLA_PREHEAT_FAN_SPEED 0
|
|
||||||
|
|
||||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
|
||||||
#define ABS_PREHEAT_HPB_TEMP 100
|
|
||||||
#define ABS_PREHEAT_FAN_SPEED 0
|
|
||||||
|
|
||||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
|
||||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
|
||||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
|
||||||
|
|
||||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
|
||||||
#define PP_PREHEAT_HPB_TEMP 100
|
|
||||||
#define PP_PREHEAT_FAN_SPEED 0
|
|
||||||
|
|
||||||
#define PET_PREHEAT_HOTEND_TEMP 240
|
|
||||||
#define PET_PREHEAT_HPB_TEMP 90
|
|
||||||
#define PET_PREHEAT_FAN_SPEED 0
|
|
||||||
|
|
||||||
#define FLEX_PREHEAT_HOTEND_TEMP 230
|
|
||||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
|
||||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
|
||||||
|
|
||||||
|
|
||||||
/*------------------------------------
|
|
||||||
THERMISTORS SETTINGS
|
|
||||||
*------------------------------------*/
|
|
||||||
|
|
||||||
//
|
|
||||||
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
|
|
||||||
//
|
|
||||||
//// Temperature sensor settings:
|
|
||||||
// -2 is thermocouple with MAX6675 (only for sensor 0)
|
|
||||||
// -1 is thermocouple with AD595
|
|
||||||
// 0 is not used
|
|
||||||
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
|
|
||||||
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
|
|
||||||
// 3 is Mendel-parts thermistor (4.7k pullup)
|
|
||||||
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
|
|
||||||
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
|
|
||||||
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
|
|
||||||
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
|
|
||||||
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
|
|
||||||
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
|
|
||||||
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
|
|
||||||
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
|
|
||||||
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
|
|
||||||
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
|
|
||||||
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
|
|
||||||
// 20 is the PT100 circuit found in the Ultimainboard V2.x
|
|
||||||
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
|
|
||||||
//
|
|
||||||
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
|
|
||||||
// (but gives greater accuracy and more stable PID)
|
|
||||||
// 51 is 100k thermistor - EPCOS (1k pullup)
|
|
||||||
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
|
|
||||||
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
|
|
||||||
//
|
|
||||||
// 1047 is Pt1000 with 4k7 pullup
|
|
||||||
// 1010 is Pt1000 with 1k pullup (non standard)
|
|
||||||
// 147 is Pt100 with 4k7 pullup
|
|
||||||
// 110 is Pt100 with 1k pullup (non standard)
|
|
||||||
|
|
||||||
#define TEMP_SENSOR_0 5
|
|
||||||
#define TEMP_SENSOR_1 0
|
|
||||||
#define TEMP_SENSOR_2 0
|
|
||||||
#define TEMP_SENSOR_BED 1
|
|
||||||
|
|
||||||
|
|
||||||
#endif //__CONFIGURATION_PRUSA_H
|
|
17
Firmware/variants/3mm-RAMBo10a-PrusaNmk2.h
Executable file → Normal file
17
Firmware/variants/3mm-RAMBo10a-PrusaNmk2.h
Executable file → Normal file
@ -43,6 +43,11 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define Z_MAX_POS 201
|
#define Z_MAX_POS 201
|
||||||
#define Z_MIN_POS 0.23
|
#define Z_MIN_POS 0.23
|
||||||
|
|
||||||
|
// Canceled home position
|
||||||
|
#define X_CANCEL_POS 50
|
||||||
|
#define Y_CANCEL_POS 180
|
||||||
|
|
||||||
|
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
@ -181,6 +186,18 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||||
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
|
// temperature runaway
|
||||||
|
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||||
|
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||||
|
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||||
|
|
||||||
/*------------------------------------
|
/*------------------------------------
|
||||||
THERMISTORS SETTINGS
|
THERMISTORS SETTINGS
|
||||||
|
16
Firmware/variants/3mm-RAMBo13a-PrusaNmk2.h
Executable file → Normal file
16
Firmware/variants/3mm-RAMBo13a-PrusaNmk2.h
Executable file → Normal file
@ -43,6 +43,10 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define Z_MAX_POS 201
|
#define Z_MAX_POS 201
|
||||||
#define Z_MIN_POS 0.23
|
#define Z_MIN_POS 0.23
|
||||||
|
|
||||||
|
// Canceled home position
|
||||||
|
#define X_CANCEL_POS 50
|
||||||
|
#define Y_CANCEL_POS 180
|
||||||
|
|
||||||
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
|
||||||
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
|
||||||
|
|
||||||
@ -181,6 +185,18 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
|||||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||||
|
|
||||||
|
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
|
||||||
|
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
|
||||||
|
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
|
||||||
|
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
|
||||||
|
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
|
||||||
|
|
||||||
|
// temperature runaway
|
||||||
|
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
|
||||||
|
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
|
||||||
|
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
|
||||||
|
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
|
||||||
|
|
||||||
/*------------------------------------
|
/*------------------------------------
|
||||||
THERMISTORS SETTINGS
|
THERMISTORS SETTINGS
|
||||||
|
0
Firmware/vector_3.cpp
Executable file → Normal file
0
Firmware/vector_3.cpp
Executable file → Normal file
0
Firmware/vector_3.h
Executable file → Normal file
0
Firmware/vector_3.h
Executable file → Normal file
0
Firmware/watchdog.cpp
Executable file → Normal file
0
Firmware/watchdog.cpp
Executable file → Normal file
0
Firmware/watchdog.h
Executable file → Normal file
0
Firmware/watchdog.h
Executable file → Normal file
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
Loading…
Reference in New Issue
Block a user