merge with upstream
This commit is contained in:
commit
d307868a90
@ -347,6 +347,9 @@ extern bool sortAlpha;
|
||||
|
||||
extern char dir_names[3][9];
|
||||
|
||||
// save/restore printing
|
||||
extern bool saved_printing;
|
||||
|
||||
extern void calculate_extruder_multipliers();
|
||||
|
||||
// Similar to the default Arduino delay function,
|
||||
|
@ -308,7 +308,7 @@ unsigned long t_fan_rising_edge = millis();
|
||||
bool mesh_bed_leveling_flag = false;
|
||||
bool mesh_bed_run_from_menu = false;
|
||||
|
||||
unsigned char lang_selected = 0;
|
||||
//unsigned char lang_selected = 0;
|
||||
int8_t FarmMode = 0;
|
||||
|
||||
bool prusa_sd_card_upload = false;
|
||||
@ -425,6 +425,10 @@ bool no_response = false;
|
||||
uint8_t important_status;
|
||||
uint8_t saved_filament_type;
|
||||
|
||||
// save/restore printing
|
||||
bool saved_printing = false;
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//=============================Private Variables=============================
|
||||
//===========================================================================
|
||||
@ -477,6 +481,14 @@ unsigned long chdkHigh = 0;
|
||||
boolean chdkActive = false;
|
||||
#endif
|
||||
|
||||
// save/restore printing
|
||||
static uint32_t saved_sdpos = 0;
|
||||
static float saved_pos[4] = { 0, 0, 0, 0 };
|
||||
// Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min.
|
||||
static float saved_feedrate2 = 0;
|
||||
static uint8_t saved_active_extruder = 0;
|
||||
static bool saved_extruder_under_pressure = false;
|
||||
|
||||
//===========================================================================
|
||||
//=============================Routines======================================
|
||||
//===========================================================================
|
||||
@ -664,11 +676,11 @@ void crashdet_detected(uint8_t mask)
|
||||
#ifdef AUTOMATIC_RECOVERY_AFTER_CRASH
|
||||
bool yesno = true;
|
||||
#else
|
||||
bool yesno = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_CRASH_DETECTED, false);
|
||||
bool yesno = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_CRASH_DETECTED), false);
|
||||
#endif
|
||||
lcd_update_enable(true);
|
||||
lcd_update(2);
|
||||
lcd_setstatuspgm(MSG_CRASH_DETECTED);
|
||||
lcd_setstatuspgm(_T(MSG_CRASH_DETECTED));
|
||||
if (yesno)
|
||||
{
|
||||
enquecommand_P(PSTR("G28 X Y"));
|
||||
@ -915,8 +927,8 @@ void factory_reset()
|
||||
void show_fw_version_warnings() {
|
||||
if (FW_DEV_VERSION == FW_VERSION_GOLD || FW_DEV_VERSION == FW_VERSION_RC) return;
|
||||
switch (FW_DEV_VERSION) {
|
||||
case(FW_VERSION_ALPHA): lcd_show_fullscreen_message_and_wait_P(MSG_FW_VERSION_ALPHA); break;
|
||||
case(FW_VERSION_BETA): lcd_show_fullscreen_message_and_wait_P(MSG_FW_VERSION_BETA); break;
|
||||
case(FW_VERSION_ALPHA): lcd_show_fullscreen_message_and_wait_P(_i("You are using firmware alpha version. This is development version. Using this version is not recommended and may cause printer damage.")); break;////MSG_FW_VERSION_ALPHA c=20 r=8
|
||||
case(FW_VERSION_BETA): lcd_show_fullscreen_message_and_wait_P(_i("You are using firmware beta version. This is development version. Using this version is not recommended and may cause printer damage.")); break;////MSG_FW_VERSION_BETA c=20 r=8
|
||||
case(FW_VERSION_DEVEL):
|
||||
case(FW_VERSION_DEBUG):
|
||||
lcd_update_enable(false);
|
||||
@ -931,7 +943,7 @@ void show_fw_version_warnings() {
|
||||
lcd_print_at_PGM(0, 3, PSTR(FW_REPOSITORY));
|
||||
lcd_wait_for_click();
|
||||
break;
|
||||
default: lcd_show_fullscreen_message_and_wait_P(MSG_FW_VERSION_UNKNOWN); break;
|
||||
default: lcd_show_fullscreen_message_and_wait_P(_i("WARNING: This is an unofficial, unsupported build. Use at your own risk!")); break;////MSG_FW_VERSION_UNKNOWN c=20 r=8
|
||||
}
|
||||
lcd_update_enable(true);
|
||||
}
|
||||
@ -1008,12 +1020,12 @@ void setup()
|
||||
|
||||
// Check startup - does nothing if bootloader sets MCUSR to 0
|
||||
byte mcu = MCUSR;
|
||||
/* if (mcu & 1) SERIAL_ECHOLNRPGM(MSG_POWERUP);
|
||||
/* if (mcu & 1) SERIAL_ECHOLNRPGM(_T(MSG_POWERUP));
|
||||
if (mcu & 2) SERIAL_ECHOLNRPGM(MSG_EXTERNAL_RESET);
|
||||
if (mcu & 4) SERIAL_ECHOLNRPGM(MSG_BROWNOUT_RESET);
|
||||
if (mcu & 8) SERIAL_ECHOLNRPGM(MSG_WATCHDOG_RESET);
|
||||
if (mcu & 32) SERIAL_ECHOLNRPGM(MSG_SOFTWARE_RESET);*/
|
||||
if (mcu & 1) puts_P(MSG_POWERUP);
|
||||
if (mcu & 1) puts_P(_T(MSG_POWERUP));
|
||||
if (mcu & 2) puts_P(MSG_EXTERNAL_RESET);
|
||||
if (mcu & 4) puts_P(MSG_BROWNOUT_RESET);
|
||||
if (mcu & 8) puts_P(MSG_WATCHDOG_RESET);
|
||||
@ -1026,9 +1038,9 @@ void setup()
|
||||
#ifdef STRING_VERSION_CONFIG_H
|
||||
#ifdef STRING_CONFIG_H_AUTHOR
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(MSG_CONFIGURATION_VER);
|
||||
SERIAL_ECHORPGM(_i(" Last Updated: "));////MSG_CONFIGURATION_VER c=0 r=0
|
||||
SERIAL_ECHOPGM(STRING_VERSION_CONFIG_H);
|
||||
SERIAL_ECHORPGM(MSG_AUTHOR);
|
||||
SERIAL_ECHORPGM(_n(" | Author: "));////MSG_AUTHOR c=0 r=0
|
||||
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
|
||||
SERIAL_ECHOPGM("Compiled: ");
|
||||
SERIAL_ECHOLNPGM(__DATE__);
|
||||
@ -1036,9 +1048,9 @@ void setup()
|
||||
#endif
|
||||
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(MSG_FREE_MEMORY);
|
||||
SERIAL_ECHORPGM(_i(" Free Memory: "));////MSG_FREE_MEMORY c=0 r=0
|
||||
SERIAL_ECHO(freeMemory());
|
||||
SERIAL_ECHORPGM(MSG_PLANNER_BUFFER_BYTES);
|
||||
SERIAL_ECHORPGM(_i(" PlannerBufferBytes: "));////MSG_PLANNER_BUFFER_BYTES c=0 r=0
|
||||
SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
|
||||
//lcd_update_enable(false); // why do we need this?? - andre
|
||||
// loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
|
||||
@ -1079,12 +1091,12 @@ void setup()
|
||||
}
|
||||
|
||||
#ifdef TMC2130_LINEARITY_CORRECTION
|
||||
#ifdef EXPERIMENTAL_FEATURES
|
||||
tmc2130_wave_fac[X_AXIS] = eeprom_read_word((uint8_t*)EEPROM_TMC2130_WAVE_X_FAC);
|
||||
tmc2130_wave_fac[Y_AXIS] = eeprom_read_word((uint8_t*)EEPROM_TMC2130_WAVE_Y_FAC);
|
||||
tmc2130_wave_fac[Z_AXIS] = eeprom_read_word((uint8_t*)EEPROM_TMC2130_WAVE_Z_FAC);
|
||||
#endif //EXPERIMENTAL_FEATURES
|
||||
tmc2130_wave_fac[E_AXIS] = eeprom_read_word((uint16_t*)EEPROM_TMC2130_WAVE_E_FAC);
|
||||
#ifdef TMC2130_LINEARITY_CORRECTION_XYZ
|
||||
tmc2130_wave_fac[X_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_WAVE_X_FAC);
|
||||
tmc2130_wave_fac[Y_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_WAVE_Y_FAC);
|
||||
tmc2130_wave_fac[Z_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_WAVE_Z_FAC);
|
||||
#endif //TMC2130_LINEARITY_CORRECTION_XYZ
|
||||
tmc2130_wave_fac[E_AXIS] = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_WAVE_E_FAC);
|
||||
if (tmc2130_wave_fac[X_AXIS] == 0xff) tmc2130_wave_fac[X_AXIS] = 0;
|
||||
if (tmc2130_wave_fac[Y_AXIS] == 0xff) tmc2130_wave_fac[Y_AXIS] = 0;
|
||||
if (tmc2130_wave_fac[Z_AXIS] == 0xff) tmc2130_wave_fac[Z_AXIS] = 0;
|
||||
@ -1258,10 +1270,34 @@ void setup()
|
||||
// In the future, somewhere here would one compare the current firmware version against the firmware version stored in the EEPROM.
|
||||
// If they differ, an update procedure may need to be performed. At the end of this block, the current firmware version
|
||||
// is being written into the EEPROM, so the update procedure will be triggered only once.
|
||||
lang_selected = eeprom_read_byte((uint8_t*)EEPROM_LANG);
|
||||
if (lang_selected >= LANG_NUM){
|
||||
lcd_mylang();
|
||||
}
|
||||
|
||||
lang_selected = eeprom_read_byte((uint8_t*)EEPROM_LANG);
|
||||
if (lang_selected >= LANG_NUM)
|
||||
{
|
||||
lcd_mylang();
|
||||
}
|
||||
lang_select(lang_selected);
|
||||
|
||||
puts_P(_n("\nNew ML support"));
|
||||
printf_P(_n(" lang_selected = %d\n"), lang_selected);
|
||||
printf_P(_n(" &_SEC_LANG = 0x%04x\n"), &_SEC_LANG);
|
||||
printf_P(_n(" sizeof(_SEC_LANG) = 0x%04x\n"), sizeof(_SEC_LANG));
|
||||
uint16_t ptr_lang_table0 = ((uint16_t)(&_SEC_LANG) + 0xff) & 0xff00;
|
||||
printf_P(_n(" &_lang_table0 = 0x%04x\n"), ptr_lang_table0);
|
||||
uint32_t _lt_magic = pgm_read_dword(((uint32_t*)(ptr_lang_table0 + 0)));
|
||||
uint16_t _lt_size = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 4)));
|
||||
uint16_t _lt_count = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 6)));
|
||||
uint16_t _lt_chsum = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 8)));
|
||||
uint16_t _lt_resv0 = pgm_read_word(((uint16_t*)(ptr_lang_table0 + 10)));
|
||||
uint32_t _lt_resv1 = pgm_read_dword(((uint32_t*)(ptr_lang_table0 + 12)));
|
||||
printf_P(_n(" _lt_magic = 0x%08lx %S\n"), _lt_magic, (_lt_magic==0x4bb45aa5)?_n("OK"):_n("NA"));
|
||||
printf_P(_n(" _lt_size = 0x%04x (%d)\n"), _lt_size, _lt_size);
|
||||
printf_P(_n(" _lt_count = 0x%04x (%d)\n"), _lt_count, _lt_count);
|
||||
printf_P(_n(" _lt_chsum = 0x%04x\n"), _lt_chsum);
|
||||
printf_P(_n(" _lt_resv0 = 0x%04x\n"), _lt_resv0);
|
||||
printf_P(_n(" _lt_resv1 = 0x%08lx\n"), _lt_resv1);
|
||||
puts_P(_n("\n"));
|
||||
|
||||
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE) == 255) {
|
||||
eeprom_write_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE, 0);
|
||||
@ -1309,15 +1345,15 @@ void setup()
|
||||
//if motherboard or printer type was changed inform user as it can indicate flashing wrong firmware version
|
||||
//if user confirms with knob, new hw version (printer and/or motherboard) is written to eeprom and message will be not shown next time
|
||||
case(0b01):
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_CHANGED_MOTHERBOARD);
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Warning: motherboard type changed.")); ////MSG_CHANGED_MOTHERBOARD c=20 r=4
|
||||
eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
|
||||
break;
|
||||
case(0b10):
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_CHANGED_PRINTER);
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Warning: printer type changed.")); ////MSG_CHANGED_PRINTER c=20 r=4
|
||||
eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
|
||||
break;
|
||||
case(0b11):
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_CHANGED_BOTH);
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Warning: both printer type and motherboard type changed.")); ////MSG_CHANGED_BOTH c=20 r=4
|
||||
eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
|
||||
eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
|
||||
break;
|
||||
@ -1325,7 +1361,7 @@ void setup()
|
||||
}
|
||||
|
||||
if (!previous_settings_retrieved) {
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_DEFAULT_SETTINGS_LOADED); //if EEPROM version or printer type was changed, inform user that default setting were loaded
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Old settings found. Default PID, Esteps etc. will be set.")); //if EEPROM version or printer type was changed, inform user that default setting were loaded////MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
|
||||
erase_eeprom_section(EEPROM_OFFSET, 156); //erase M500 part of eeprom
|
||||
}
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) {
|
||||
@ -1338,26 +1374,26 @@ void setup()
|
||||
// Reset the babystepping values, so the printer will not move the Z axis up when the babystepping is enabled.
|
||||
eeprom_update_word((uint16_t*)EEPROM_BABYSTEP_Z, 0);
|
||||
// Show the message.
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_FOLLOW_CALIBRATION_FLOW);
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_FOLLOW_CALIBRATION_FLOW));
|
||||
}
|
||||
else if (calibration_status() == CALIBRATION_STATUS_LIVE_ADJUST) {
|
||||
// Show the message.
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_BABYSTEP_Z_NOT_SET);
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_BABYSTEP_Z_NOT_SET));
|
||||
lcd_update_enable(true);
|
||||
}
|
||||
else if (calibration_status() == CALIBRATION_STATUS_CALIBRATED && temp_cal_active == true && calibration_status_pinda() == false) {
|
||||
//lcd_show_fullscreen_message_and_wait_P(MSG_PINDA_NOT_CALIBRATED);
|
||||
//lcd_show_fullscreen_message_and_wait_P(_i("Temperature calibration has not been run yet"));////MSG_PINDA_NOT_CALIBRATED c=20 r=4
|
||||
lcd_update_enable(true);
|
||||
}
|
||||
else if (calibration_status() == CALIBRATION_STATUS_Z_CALIBRATION) {
|
||||
// Show the message.
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_FOLLOW_CALIBRATION_FLOW);
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_FOLLOW_CALIBRATION_FLOW));
|
||||
}
|
||||
}
|
||||
|
||||
#if !defined (DEBUG_DISABLE_FORCE_SELFTEST) && defined (TMC2130)
|
||||
if (force_selftest_if_fw_version() && calibration_status() < CALIBRATION_STATUS_ASSEMBLED) {
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_FORCE_SELFTEST);
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Selftest will be run to calibrate accurate sensorless rehoming."));////MSG_FORCE_SELFTEST c=20 r=8
|
||||
update_current_firmware_version_to_eeprom();
|
||||
lcd_selftest();
|
||||
}
|
||||
@ -1394,12 +1430,12 @@ void setup()
|
||||
#ifdef UVLO_SUPPORT
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 1) { //previous print was terminated by UVLO
|
||||
/*
|
||||
if (lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_RECOVER_PRINT, false)) recover_print();
|
||||
if (lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_RECOVER_PRINT), false)) recover_print();
|
||||
else {
|
||||
eeprom_update_byte((uint8_t*)EEPROM_UVLO, 0);
|
||||
lcd_update_enable(true);
|
||||
lcd_update(2);
|
||||
lcd_setstatuspgm(WELCOME_MSG);
|
||||
lcd_setstatuspgm(_T(WELCOME_MSG));
|
||||
}
|
||||
*/
|
||||
manage_heater(); // Update temperatures
|
||||
@ -1420,12 +1456,12 @@ void setup()
|
||||
#ifdef DEBUG_UVLO_AUTOMATIC_RECOVER
|
||||
MYSERIAL.println("Normal recovery!");
|
||||
#endif
|
||||
if ( lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_RECOVER_PRINT, false) ) recover_print(0);
|
||||
if ( lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_RECOVER_PRINT), false) ) recover_print(0);
|
||||
else {
|
||||
eeprom_update_byte((uint8_t*)EEPROM_UVLO, 0);
|
||||
lcd_update_enable(true);
|
||||
lcd_update(2);
|
||||
lcd_setstatuspgm(WELCOME_MSG);
|
||||
lcd_setstatuspgm(_T(WELCOME_MSG));
|
||||
}
|
||||
|
||||
}
|
||||
@ -1444,6 +1480,7 @@ void fsensor_init() {
|
||||
int pat9125 = pat9125_init();
|
||||
printf_P(PSTR("PAT9125_init:%d\n"), pat9125);
|
||||
uint8_t fsensor = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR);
|
||||
filament_autoload_enabled=eeprom_read_byte((uint8_t*)EEPROM_FSENS_AUTOLOAD_ENABLED);
|
||||
if (!pat9125)
|
||||
{
|
||||
fsensor = 0; //disable sensor
|
||||
@ -1620,7 +1657,7 @@ void loop()
|
||||
if(card.logging)
|
||||
process_commands();
|
||||
else
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_OK);
|
||||
SERIAL_PROTOCOLLNRPGM(_T(MSG_OK));
|
||||
} else {
|
||||
card.closefile();
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_FILE_SAVED);
|
||||
@ -1870,7 +1907,7 @@ static float probe_pt(float x, float y, float z_before) {
|
||||
run_z_probe();
|
||||
float measured_z = current_position[Z_AXIS];
|
||||
|
||||
SERIAL_PROTOCOLRPGM(MSG_BED);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_BED));
|
||||
SERIAL_PROTOCOLPGM(" x: ");
|
||||
SERIAL_PROTOCOL(x);
|
||||
SERIAL_PROTOCOLPGM(" y: ");
|
||||
@ -1933,9 +1970,9 @@ bool check_commands() {
|
||||
#ifdef TMC2130
|
||||
bool calibrate_z_auto()
|
||||
{
|
||||
//lcd_display_message_fullscreen_P(MSG_CALIBRATE_Z_AUTO);
|
||||
//lcd_display_message_fullscreen_P(_T(MSG_CALIBRATE_Z_AUTO));
|
||||
lcd_implementation_clear();
|
||||
lcd_print_at_PGM(0,1, MSG_CALIBRATE_Z_AUTO);
|
||||
lcd_print_at_PGM(0,1, _T(MSG_CALIBRATE_Z_AUTO));
|
||||
bool endstops_enabled = enable_endstops(true);
|
||||
int axis_up_dir = -home_dir(Z_AXIS);
|
||||
tmc2130_home_enter(Z_AXIS_MASK);
|
||||
@ -2578,7 +2615,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
|
||||
// Home in the XY plane.
|
||||
//set_destination_to_current();
|
||||
setup_for_endstop_move();
|
||||
lcd_display_message_fullscreen_P(MSG_AUTO_HOME);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_AUTO_HOME));
|
||||
home_xy();
|
||||
|
||||
enable_endstops(false);
|
||||
@ -2606,15 +2643,15 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
|
||||
{
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
#ifdef STEEL_SHEET
|
||||
bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_STEEL_SHEET_CHECK, false, false);
|
||||
if(result) lcd_show_fullscreen_message_and_wait_P(MSG_REMOVE_STEEL_SHEET);
|
||||
bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false);
|
||||
if(result) lcd_show_fullscreen_message_and_wait_P(_T(MSG_REMOVE_STEEL_SHEET));
|
||||
#endif //STEEL_SHEET
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_CONFIRM_NOZZLE_CLEAN);
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_PAPER);
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_CONFIRM_NOZZLE_CLEAN));
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_PAPER));
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
lcd_display_message_fullscreen_P(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1));
|
||||
lcd_implementation_print_at(0, 2, 1);
|
||||
lcd_printPGM(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2);
|
||||
lcd_printPGM(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));
|
||||
}
|
||||
// Move the print head close to the bed.
|
||||
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
|
||||
@ -2707,7 +2744,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
|
||||
{
|
||||
// Calibration valid, the machine should be able to print. Advise the user to run the V2Calibration.gcode.
|
||||
calibration_status_store(CALIBRATION_STATUS_LIVE_ADJUST);
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) != 1) lcd_show_fullscreen_message_and_wait_P(MSG_BABYSTEP_Z_NOT_SET);
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) != 1) lcd_show_fullscreen_message_and_wait_P(_T(MSG_BABYSTEP_Z_NOT_SET));
|
||||
final_result = true;
|
||||
}
|
||||
}
|
||||
@ -2743,7 +2780,7 @@ void gcode_M114()
|
||||
SERIAL_PROTOCOLPGM(" E:");
|
||||
SERIAL_PROTOCOL(current_position[E_AXIS]);
|
||||
|
||||
SERIAL_PROTOCOLRPGM(MSG_COUNT_X);
|
||||
SERIAL_PROTOCOLRPGM(_n(" Count X: "));////MSG_COUNT_X c=0 r=0
|
||||
SERIAL_PROTOCOL(float(st_get_position(X_AXIS)) / axis_steps_per_unit[X_AXIS]);
|
||||
SERIAL_PROTOCOLPGM(" Y:");
|
||||
SERIAL_PROTOCOL(float(st_get_position(Y_AXIS)) / axis_steps_per_unit[Y_AXIS]);
|
||||
@ -2764,7 +2801,7 @@ void gcode_M701()
|
||||
custom_message = true;
|
||||
custom_message_type = 2;
|
||||
|
||||
lcd_setstatuspgm(MSG_LOADING_FILAMENT);
|
||||
lcd_setstatuspgm(_T(MSG_LOADING_FILAMENT));
|
||||
current_position[E_AXIS] += 70;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder); //fast sequence
|
||||
|
||||
@ -2777,7 +2814,7 @@ void gcode_M701()
|
||||
noTone(BEEPER);
|
||||
|
||||
if (!farm_mode && loading_flag) {
|
||||
bool clean = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_FILAMENT_CLEAN, false, true);
|
||||
bool clean = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_FILAMENT_CLEAN), false, true);
|
||||
|
||||
while (!clean) {
|
||||
lcd_update_enable(true);
|
||||
@ -2785,14 +2822,14 @@ void gcode_M701()
|
||||
current_position[E_AXIS] += 25;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 100 / 60, active_extruder); //slow sequence
|
||||
st_synchronize();
|
||||
clean = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_FILAMENT_CLEAN, false, true);
|
||||
clean = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_FILAMENT_CLEAN), false, true);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
lcd_update_enable(true);
|
||||
lcd_update(2);
|
||||
lcd_setstatuspgm(WELCOME_MSG);
|
||||
lcd_setstatuspgm(_T(WELCOME_MSG));
|
||||
disable_z();
|
||||
loading_flag = false;
|
||||
custom_message = false;
|
||||
@ -3056,7 +3093,7 @@ void process_commands()
|
||||
disable_e2();
|
||||
delay(100);
|
||||
|
||||
//LCD_ALERTMESSAGEPGM(MSG_FILAMENTCHANGE);
|
||||
//LCD_ALERTMESSAGEPGM(_T(MSG_FILAMENTCHANGE));
|
||||
uint8_t cnt=0;
|
||||
int counterBeep = 0;
|
||||
lcd_wait_interact();
|
||||
@ -3223,7 +3260,7 @@ void process_commands()
|
||||
codenum = 0;
|
||||
if(code_seen('P')) codenum = code_value(); // milliseconds to wait
|
||||
if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
|
||||
if(codenum != 0) LCD_MESSAGERPGM(MSG_DWELL);
|
||||
if(codenum != 0) LCD_MESSAGERPGM(_i("Sleep..."));////MSG_DWELL c=0 r=0
|
||||
st_synchronize();
|
||||
codenum += millis(); // keep track of when we started waiting
|
||||
previous_millis_cmd = millis();
|
||||
@ -3416,7 +3453,7 @@ void process_commands()
|
||||
feedrate = homing_feedrate[Z_AXIS];
|
||||
|
||||
run_z_probe();
|
||||
SERIAL_PROTOCOLPGM(MSG_BED);
|
||||
SERIAL_PROTOCOLPGM(_T(MSG_BED));
|
||||
SERIAL_PROTOCOLPGM(" X: ");
|
||||
SERIAL_PROTOCOL(current_position[X_AXIS]);
|
||||
SERIAL_PROTOCOLPGM(" Y: ");
|
||||
@ -3448,7 +3485,7 @@ void process_commands()
|
||||
feedrate = homing_feedrate[Z_AXIS];
|
||||
|
||||
find_bed_induction_sensor_point_z(-10.f, 3);
|
||||
SERIAL_PROTOCOLRPGM(MSG_BED);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_BED));
|
||||
SERIAL_PROTOCOLPGM(" X: ");
|
||||
MYSERIAL.print(current_position[X_AXIS], 5);
|
||||
SERIAL_PROTOCOLPGM(" Y: ");
|
||||
@ -3493,8 +3530,8 @@ void process_commands()
|
||||
enquecommand_front_P((PSTR("G28 W0")));
|
||||
break;
|
||||
}
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_TEMP_CAL_WARNING);
|
||||
bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_STEEL_SHEET_CHECK, false, false);
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Stable ambient temperature 21-26C is needed a rigid stand is required."));////MSG_TEMP_CAL_WARNING c=20 r=4
|
||||
bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false);
|
||||
|
||||
if (result)
|
||||
{
|
||||
@ -3504,7 +3541,7 @@ void process_commands()
|
||||
current_position[Y_AXIS] = 180;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
|
||||
st_synchronize();
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_REMOVE_STEEL_SHEET);
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_REMOVE_STEEL_SHEET));
|
||||
current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + 1);
|
||||
current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
|
||||
@ -3539,7 +3576,7 @@ void process_commands()
|
||||
custom_message = true;
|
||||
custom_message_type = 4;
|
||||
custom_message_state = 1;
|
||||
custom_message = MSG_TEMP_CALIBRATION;
|
||||
custom_message = _T(MSG_TEMP_CALIBRATION);
|
||||
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
|
||||
current_position[X_AXIS] = PINDA_PREHEAT_X;
|
||||
@ -3660,7 +3697,7 @@ void process_commands()
|
||||
custom_message = true;
|
||||
custom_message_type = 4;
|
||||
custom_message_state = 1;
|
||||
custom_message = MSG_TEMP_CALIBRATION;
|
||||
custom_message = _T(MSG_TEMP_CALIBRATION);
|
||||
current_position[X_AXIS] = PINDA_PREHEAT_X;
|
||||
current_position[Y_AXIS] = PINDA_PREHEAT_Y;
|
||||
current_position[Z_AXIS] = PINDA_PREHEAT_Z;
|
||||
@ -3749,7 +3786,7 @@ void process_commands()
|
||||
disable_e1();
|
||||
disable_e2();
|
||||
setTargetBed(0); //set bed target temperature back to 0
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_TEMP_CALIBRATION_DONE);
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_TEMP_CALIBRATION_DONE));
|
||||
temp_cal_active = true;
|
||||
eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, 1);
|
||||
lcd_update_enable(true);
|
||||
@ -3969,15 +4006,15 @@ void process_commands()
|
||||
// Go down until endstop is hit
|
||||
const float Z_CALIBRATION_THRESHOLD = 1.f;
|
||||
if (!find_bed_induction_sensor_point_z((has_z && mesh_point > 0) ? z0 - Z_CALIBRATION_THRESHOLD : -10.f)) { //if we have data from z calibration max allowed difference is 1mm for each point, if we dont have data max difference is 10mm from initial point
|
||||
kill_message = MSG_BED_LEVELING_FAILED_POINT_LOW;
|
||||
kill_message = _T(MSG_BED_LEVELING_FAILED_POINT_LOW);
|
||||
break;
|
||||
}
|
||||
if (MESH_HOME_Z_SEARCH - current_position[Z_AXIS] < 0.1f) {
|
||||
kill_message = MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED;
|
||||
kill_message = _i("Bed leveling failed. Sensor disconnected or cable broken. Waiting for reset.");////MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED c=20 r=4
|
||||
break;
|
||||
}
|
||||
if (has_z && fabs(z0 - current_position[Z_AXIS]) > Z_CALIBRATION_THRESHOLD) { //if we have data from z calibration, max. allowed difference is 1mm for each point
|
||||
kill_message = MSG_BED_LEVELING_FAILED_POINT_HIGH;
|
||||
kill_message = _i("Bed leveling failed. Sensor triggered too high. Waiting for reset.");////MSG_BED_LEVELING_FAILED_POINT_HIGH c=20 r=4
|
||||
break;
|
||||
}
|
||||
#ifdef SUPPORT_VERBOSITY
|
||||
@ -4301,7 +4338,7 @@ void process_commands()
|
||||
if (!hasP && !hasS && *src != '\0') {
|
||||
lcd_setstatus(src);
|
||||
} else {
|
||||
LCD_MESSAGERPGM(MSG_USERWAIT);
|
||||
LCD_MESSAGERPGM(_i("Wait for user..."));////MSG_USERWAIT c=0 r=0
|
||||
}
|
||||
|
||||
lcd_ignore_click(); //call lcd_ignore_click aslo for else ???
|
||||
@ -4329,14 +4366,14 @@ void process_commands()
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
}
|
||||
if (IS_SD_PRINTING)
|
||||
LCD_MESSAGERPGM(MSG_RESUMING);
|
||||
LCD_MESSAGERPGM(_i("Resuming print"));////MSG_RESUMING c=0 r=0
|
||||
else
|
||||
LCD_MESSAGERPGM(WELCOME_MSG);
|
||||
LCD_MESSAGERPGM(_T(WELCOME_MSG));
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case 17:
|
||||
LCD_MESSAGERPGM(MSG_NO_MOVE);
|
||||
LCD_MESSAGERPGM(_i("No move."));////MSG_NO_MOVE c=0 r=0
|
||||
enable_x();
|
||||
enable_y();
|
||||
enable_z();
|
||||
@ -4347,9 +4384,9 @@ void process_commands()
|
||||
|
||||
#ifdef SDSUPPORT
|
||||
case 20: // M20 - list SD card
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_BEGIN_FILE_LIST);
|
||||
SERIAL_PROTOCOLLNRPGM(_i("Begin file list"));////MSG_BEGIN_FILE_LIST c=0 r=0
|
||||
card.ls();
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_END_FILE_LIST);
|
||||
SERIAL_PROTOCOLLNRPGM(_i("End file list"));////MSG_END_FILE_LIST c=0 r=0
|
||||
break;
|
||||
case 21: // M21 - init SD card
|
||||
|
||||
@ -4888,7 +4925,7 @@ Sigma_Exit:
|
||||
}
|
||||
#else
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_ERR_NO_THERMISTORS);
|
||||
SERIAL_ERRORLNRPGM(_i("No thermistors - no temperature"));////MSG_ERR_NO_THERMISTORS c=0 r=0
|
||||
#endif
|
||||
|
||||
SERIAL_PROTOCOLPGM(" @:");
|
||||
@ -4959,7 +4996,7 @@ Sigma_Exit:
|
||||
if(setTargetedHotend(109)){
|
||||
break;
|
||||
}
|
||||
LCD_MESSAGERPGM(MSG_HEATING);
|
||||
LCD_MESSAGERPGM(_T(MSG_HEATING));
|
||||
heating_status = 1;
|
||||
if (farm_mode) { prusa_statistics(1); };
|
||||
|
||||
@ -4995,7 +5032,7 @@ Sigma_Exit:
|
||||
|
||||
wait_for_heater(codenum); //loops until target temperature is reached
|
||||
|
||||
LCD_MESSAGERPGM(MSG_HEATING_COMPLETE);
|
||||
LCD_MESSAGERPGM(_T(MSG_HEATING_COMPLETE));
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
heating_status = 2;
|
||||
if (farm_mode) { prusa_statistics(2); };
|
||||
@ -5006,7 +5043,7 @@ Sigma_Exit:
|
||||
break;
|
||||
case 190: // M190 - Wait for bed heater to reach target.
|
||||
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
|
||||
LCD_MESSAGERPGM(MSG_BED_HEATING);
|
||||
LCD_MESSAGERPGM(_T(MSG_BED_HEATING));
|
||||
heating_status = 3;
|
||||
if (farm_mode) { prusa_statistics(1); };
|
||||
if (code_seen('S'))
|
||||
@ -5046,7 +5083,7 @@ Sigma_Exit:
|
||||
manage_inactivity();
|
||||
lcd_update();
|
||||
}
|
||||
LCD_MESSAGERPGM(MSG_BED_DONE);
|
||||
LCD_MESSAGERPGM(_T(MSG_BED_DONE));
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
heating_status = 4;
|
||||
|
||||
@ -5083,7 +5120,7 @@ Sigma_Exit:
|
||||
|
||||
#ifdef ULTIPANEL
|
||||
powersupply = true;
|
||||
LCD_MESSAGERPGM(WELCOME_MSG);
|
||||
LCD_MESSAGERPGM(_T(WELCOME_MSG));
|
||||
lcd_update();
|
||||
#endif
|
||||
break;
|
||||
@ -5114,7 +5151,7 @@ Sigma_Exit:
|
||||
MSGOFF = "Vypnuto"
|
||||
"Prusai3"" ""vypnuto""."
|
||||
|
||||
"Prusa i3"" "MSG_ALL[lang_selected][50]"."
|
||||
"Prusa i3"" "_T(MSG_ALL)[lang_selected][50]"."
|
||||
*/
|
||||
lcd_update();
|
||||
#endif
|
||||
@ -5239,59 +5276,59 @@ Sigma_Exit:
|
||||
enable_endstops(true) ;
|
||||
break;
|
||||
case 119: // M119
|
||||
SERIAL_PROTOCOLRPGM(MSG_M119_REPORT);
|
||||
SERIAL_PROTOCOLRPGM(_i("Reporting endstop status"));////MSG_M119_REPORT c=0 r=0
|
||||
SERIAL_PROTOCOLLN("");
|
||||
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
|
||||
SERIAL_PROTOCOLRPGM(MSG_X_MIN);
|
||||
SERIAL_PROTOCOLRPGM(_n("x_min: "));////MSG_X_MIN c=0 r=0
|
||||
if(READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING){
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
|
||||
}else{
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
|
||||
}
|
||||
SERIAL_PROTOCOLLN("");
|
||||
#endif
|
||||
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
|
||||
SERIAL_PROTOCOLRPGM(MSG_X_MAX);
|
||||
SERIAL_PROTOCOLRPGM(_n("x_max: "));////MSG_X_MAX c=0 r=0
|
||||
if(READ(X_MAX_PIN)^X_MAX_ENDSTOP_INVERTING){
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
|
||||
}else{
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
|
||||
}
|
||||
SERIAL_PROTOCOLLN("");
|
||||
#endif
|
||||
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
|
||||
SERIAL_PROTOCOLRPGM(MSG_Y_MIN);
|
||||
SERIAL_PROTOCOLRPGM(_n("y_min: "));////MSG_Y_MIN c=0 r=0
|
||||
if(READ(Y_MIN_PIN)^Y_MIN_ENDSTOP_INVERTING){
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
|
||||
}else{
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
|
||||
}
|
||||
SERIAL_PROTOCOLLN("");
|
||||
#endif
|
||||
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
|
||||
SERIAL_PROTOCOLRPGM(MSG_Y_MAX);
|
||||
SERIAL_PROTOCOLRPGM(_n("y_max: "));////MSG_Y_MAX c=0 r=0
|
||||
if(READ(Y_MAX_PIN)^Y_MAX_ENDSTOP_INVERTING){
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
|
||||
}else{
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
|
||||
}
|
||||
SERIAL_PROTOCOLLN("");
|
||||
#endif
|
||||
#if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
|
||||
SERIAL_PROTOCOLRPGM(MSG_Z_MIN);
|
||||
if(READ(Z_MIN_PIN)^Z_MIN_ENDSTOP_INVERTING){
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
|
||||
}else{
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
|
||||
}
|
||||
SERIAL_PROTOCOLLN("");
|
||||
#endif
|
||||
#if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
|
||||
SERIAL_PROTOCOLRPGM(MSG_Z_MAX);
|
||||
if(READ(Z_MAX_PIN)^Z_MAX_ENDSTOP_INVERTING){
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_HIT);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_HIT));
|
||||
}else{
|
||||
SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_ENDSTOP_OPEN));
|
||||
}
|
||||
SERIAL_PROTOCOLLN("");
|
||||
#endif
|
||||
@ -5320,7 +5357,7 @@ Sigma_Exit:
|
||||
tmp_extruder = code_value();
|
||||
if(tmp_extruder >= EXTRUDERS) {
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHO(MSG_M200_INVALID_EXTRUDER);
|
||||
SERIAL_ECHO(_i("M200 Invalid extruder "));////MSG_M200_INVALID_EXTRUDER c=0 r=0
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -5602,7 +5639,7 @@ Sigma_Exit:
|
||||
}
|
||||
}
|
||||
else if (servo_index >= 0) {
|
||||
SERIAL_PROTOCOL(MSG_OK);
|
||||
SERIAL_PROTOCOL(_T(MSG_OK));
|
||||
SERIAL_PROTOCOL(" Servo ");
|
||||
SERIAL_PROTOCOL(servo_index);
|
||||
SERIAL_PROTOCOL(": ");
|
||||
@ -5650,7 +5687,7 @@ Sigma_Exit:
|
||||
#endif
|
||||
|
||||
updatePID();
|
||||
SERIAL_PROTOCOLRPGM(MSG_OK);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_OK));
|
||||
SERIAL_PROTOCOL(" p:");
|
||||
SERIAL_PROTOCOL(Kp);
|
||||
SERIAL_PROTOCOL(" i:");
|
||||
@ -5674,7 +5711,7 @@ Sigma_Exit:
|
||||
if(code_seen('D')) bedKd = scalePID_d(code_value());
|
||||
|
||||
updatePID();
|
||||
SERIAL_PROTOCOLRPGM(MSG_OK);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_OK));
|
||||
SERIAL_PROTOCOL(" p:");
|
||||
SERIAL_PROTOCOL(bedKp);
|
||||
SERIAL_PROTOCOL(" i:");
|
||||
@ -5802,7 +5839,7 @@ Sigma_Exit:
|
||||
{
|
||||
zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(CAT4(MSG_ZPROBE_ZOFFSET, " ", MSG_OK,PSTR("")));
|
||||
SERIAL_ECHOLNRPGM(CAT4(MSG_ZPROBE_ZOFFSET, " ", _T(MSG_OK),PSTR("")));
|
||||
SERIAL_PROTOCOLLN("");
|
||||
}
|
||||
else
|
||||
@ -5925,7 +5962,7 @@ Sigma_Exit:
|
||||
fanSpeed = 0;
|
||||
unsigned long waiting_start_time = millis();
|
||||
uint8_t wait_for_user_state = 0;
|
||||
lcd_display_message_fullscreen_P(MSG_PRESS_TO_UNLOAD);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_PRESS_TO_UNLOAD));
|
||||
while (!(wait_for_user_state == 0 && lcd_clicked())){
|
||||
|
||||
//cnt++;
|
||||
@ -5967,7 +6004,7 @@ Sigma_Exit:
|
||||
delay_keep_alive(4);
|
||||
|
||||
if (millis() > waiting_start_time + (unsigned long)M600_TIMEOUT * 1000) {
|
||||
lcd_display_message_fullscreen_P(MSG_PRESS_TO_PREHEAT);
|
||||
lcd_display_message_fullscreen_P(_i("Press knob to preheat nozzle and continue."));////MSG_PRESS_TO_PREHEAT c=20 r=4
|
||||
wait_for_user_state = 1;
|
||||
setTargetHotend(0, 0);
|
||||
setTargetHotend(0, 1);
|
||||
@ -5991,7 +6028,7 @@ Sigma_Exit:
|
||||
case 2:
|
||||
|
||||
if (abs(degTargetHotend(active_extruder) - degHotend(active_extruder)) < 1) {
|
||||
lcd_display_message_fullscreen_P(MSG_PRESS_TO_UNLOAD);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_PRESS_TO_UNLOAD));
|
||||
waiting_start_time = millis();
|
||||
wait_for_user_state = 0;
|
||||
}
|
||||
@ -6011,10 +6048,10 @@ Sigma_Exit:
|
||||
|
||||
|
||||
// Unload filament
|
||||
lcd_display_message_fullscreen_P(MSG_UNLOADING_FILAMENT);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_UNLOADING_FILAMENT));
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
custom_message = true;
|
||||
lcd_setstatuspgm(MSG_UNLOADING_FILAMENT);
|
||||
lcd_setstatuspgm(_T(MSG_UNLOADING_FILAMENT));
|
||||
|
||||
if (code_seen('L'))
|
||||
{
|
||||
@ -6088,7 +6125,7 @@ Sigma_Exit:
|
||||
//finish moves
|
||||
st_synchronize();
|
||||
|
||||
lcd_display_message_fullscreen_P(MSG_PULL_OUT_FILAMENT);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_PULL_OUT_FILAMENT));
|
||||
|
||||
//disable extruder steppers so filament can be removed
|
||||
disable_e0();
|
||||
@ -6107,8 +6144,8 @@ Sigma_Exit:
|
||||
WRITE(BEEPER, LOW);
|
||||
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
lcd_change_fil_state = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_UNLOAD_SUCCESSFUL, false, true);
|
||||
if (lcd_change_fil_state == 0) lcd_show_fullscreen_message_and_wait_P(MSG_CHECK_IDLER);
|
||||
lcd_change_fil_state = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Was filament unload successful?"), false, true);////MSG_UNLOAD_SUCCESSFUL c=20 r=2
|
||||
if (lcd_change_fil_state == 0) lcd_show_fullscreen_message_and_wait_P(_i("Please open idler and remove filament manually."));////MSG_CHECK_IDLER c=20 r=4
|
||||
//lcd_return_to_status();
|
||||
lcd_update_enable(true);
|
||||
|
||||
@ -6282,7 +6319,7 @@ Sigma_Exit:
|
||||
sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp);
|
||||
enquecommand(cmd);
|
||||
|
||||
lcd_setstatuspgm(WELCOME_MSG);
|
||||
lcd_setstatuspgm(_T(WELCOME_MSG));
|
||||
custom_message = false;
|
||||
custom_message_type = 0;
|
||||
|
||||
@ -6329,7 +6366,7 @@ Sigma_Exit:
|
||||
break;
|
||||
}
|
||||
|
||||
LCD_MESSAGERPGM(MSG_PLEASE_WAIT);
|
||||
LCD_MESSAGERPGM(_T(MSG_PLEASE_WAIT));
|
||||
|
||||
SERIAL_PROTOCOLPGM("Wait for PINDA target temperature:");
|
||||
SERIAL_PROTOCOL(setTargetPinda);
|
||||
@ -6338,8 +6375,6 @@ Sigma_Exit:
|
||||
codenum = millis();
|
||||
cancel_heatup = false;
|
||||
|
||||
KEEPALIVE_STATE(NOT_BUSY);
|
||||
|
||||
while ((!cancel_heatup) && current_temperature_pinda < setTargetPinda) {
|
||||
if ((millis() - codenum) > 1000) //Print Temp Reading every 1 second while waiting.
|
||||
{
|
||||
@ -6354,7 +6389,7 @@ Sigma_Exit:
|
||||
manage_inactivity();
|
||||
lcd_update();
|
||||
}
|
||||
LCD_MESSAGERPGM(MSG_OK);
|
||||
LCD_MESSAGERPGM(_T(MSG_OK));
|
||||
|
||||
break;
|
||||
}
|
||||
@ -6626,7 +6661,7 @@ Sigma_Exit:
|
||||
#endif //PAT9125
|
||||
custom_message = true;
|
||||
custom_message_type = 2;
|
||||
lcd_setstatuspgm(MSG_UNLOADING_FILAMENT);
|
||||
lcd_setstatuspgm(_T(MSG_UNLOADING_FILAMENT));
|
||||
|
||||
// extr_unload2();
|
||||
|
||||
@ -6640,7 +6675,7 @@ Sigma_Exit:
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1000 / 60, active_extruder);
|
||||
st_synchronize();
|
||||
|
||||
lcd_display_message_fullscreen_P(MSG_PULL_OUT_FILAMENT);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_PULL_OUT_FILAMENT));
|
||||
|
||||
//disable extruder steppers so filament can be removed
|
||||
disable_e0();
|
||||
@ -6662,7 +6697,7 @@ Sigma_Exit:
|
||||
|
||||
lcd_update_enable(true);
|
||||
|
||||
lcd_setstatuspgm(WELCOME_MSG);
|
||||
lcd_setstatuspgm(_T(WELCOME_MSG));
|
||||
custom_message = false;
|
||||
custom_message_type = 0;
|
||||
#ifdef PAT9125
|
||||
@ -6753,7 +6788,7 @@ Sigma_Exit:
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOPGM("T");
|
||||
SERIAL_PROTOCOLLN((int)tmp_extruder);
|
||||
SERIAL_ECHOLNRPGM(MSG_INVALID_EXTRUDER);
|
||||
SERIAL_ECHOLNRPGM(_n("Invalid extruder"));////MSG_INVALID_EXTRUDER c=0 r=0
|
||||
}
|
||||
else {
|
||||
boolean make_move = false;
|
||||
@ -6785,7 +6820,7 @@ Sigma_Exit:
|
||||
}
|
||||
#endif
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(MSG_ACTIVE_EXTRUDER);
|
||||
SERIAL_ECHORPGM(_n("Active Extruder: "));////MSG_ACTIVE_EXTRUDER c=0 r=0
|
||||
SERIAL_PROTOCOLLN((int)active_extruder);
|
||||
}
|
||||
|
||||
@ -6855,10 +6890,10 @@ void FlushSerialRequestResend()
|
||||
{
|
||||
//char cmdbuffer[bufindr][100]="Resend:";
|
||||
MYSERIAL.flush();
|
||||
SERIAL_PROTOCOLRPGM(MSG_RESEND);
|
||||
SERIAL_PROTOCOLRPGM(_i("Resend: "));////MSG_RESEND c=0 r=0
|
||||
SERIAL_PROTOCOLLN(gcode_LastN + 1);
|
||||
previous_millis_cmd = millis();
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_OK);
|
||||
SERIAL_PROTOCOLLNRPGM(_T(MSG_OK));
|
||||
}
|
||||
|
||||
// Confirm the execution of a command, if sent from a serial line.
|
||||
@ -6867,7 +6902,7 @@ void ClearToSend()
|
||||
{
|
||||
previous_millis_cmd = millis();
|
||||
if (CMDBUFFER_CURRENT_TYPE == CMDBUFFER_CURRENT_TYPE_USB)
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_OK);
|
||||
SERIAL_PROTOCOLLNRPGM(_T(MSG_OK));
|
||||
}
|
||||
|
||||
#if MOTHERBOARD == BOARD_RAMBO_MINI_1_0 || MOTHERBOARD == BOARD_RAMBO_MINI_1_3
|
||||
@ -7163,7 +7198,7 @@ static void handleSafetyTimer()
|
||||
#error Implemented only for one extruder.
|
||||
#endif //(EXTRUDERS > 1)
|
||||
static Timer safetyTimer;
|
||||
if (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == 4)
|
||||
if (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == 4) || saved_printing
|
||||
|| (lcd_commands_type == LCD_COMMAND_V2_CAL) || (!degTargetBed() && !degTargetHotend(0)))
|
||||
{
|
||||
safetyTimer.stop();
|
||||
@ -7172,11 +7207,11 @@ static void handleSafetyTimer()
|
||||
{
|
||||
safetyTimer.start();
|
||||
}
|
||||
else if (safetyTimer.expired(1800000ul))
|
||||
else if (safetyTimer.expired(1800000ul)) //30 min
|
||||
{
|
||||
setTargetBed(0);
|
||||
setTargetHotend(0, 0);
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_BED_HEATING_SAFETY_DISABLED);
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Heating disabled by safety timer."));////MSG_BED_HEATING_SAFETY_DISABLED c=0 r=0
|
||||
}
|
||||
}
|
||||
#endif //SAFETYTIMER
|
||||
@ -7205,9 +7240,9 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s
|
||||
lcd_update_enable(false);
|
||||
lcd_implementation_clear();
|
||||
lcd.setCursor(0, 0);
|
||||
lcd_printPGM(MSG_ERROR);
|
||||
lcd_printPGM(_T(MSG_ERROR));
|
||||
lcd.setCursor(0, 2);
|
||||
lcd_printPGM(MSG_PREHEAT_NOZZLE);
|
||||
lcd_printPGM(_T(MSG_PREHEAT_NOZZLE));
|
||||
delay(2000);
|
||||
lcd_implementation_clear();
|
||||
lcd_update_enable(true);
|
||||
@ -7332,12 +7367,12 @@ void kill(const char *full_screen_message, unsigned char id)
|
||||
pinMode(PS_ON_PIN,INPUT);
|
||||
#endif
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_ERR_KILLED);
|
||||
SERIAL_ERRORLNRPGM(_i("Printer halted. kill() called!"));////MSG_ERR_KILLED c=0 r=0
|
||||
if (full_screen_message != NULL) {
|
||||
SERIAL_ERRORLNRPGM(full_screen_message);
|
||||
lcd_display_message_fullscreen_P(full_screen_message);
|
||||
} else {
|
||||
LCD_ALERTMESSAGERPGM(MSG_KILLED);
|
||||
LCD_ALERTMESSAGERPGM(_i("KILLED. "));////MSG_KILLED c=0 r=0
|
||||
}
|
||||
|
||||
// FMC small patch to update the LCD before ending
|
||||
@ -7365,8 +7400,8 @@ void Stop()
|
||||
Stopped = true;
|
||||
Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
|
||||
LCD_MESSAGERPGM(MSG_STOPPED);
|
||||
SERIAL_ERRORLNRPGM(_T(MSG_ERR_STOPPED));
|
||||
LCD_MESSAGERPGM(_T(MSG_STOPPED));
|
||||
}
|
||||
}
|
||||
|
||||
@ -7450,19 +7485,19 @@ bool setTargetedHotend(int code){
|
||||
SERIAL_ECHO_START;
|
||||
switch(code){
|
||||
case 104:
|
||||
SERIAL_ECHORPGM(MSG_M104_INVALID_EXTRUDER);
|
||||
SERIAL_ECHORPGM(_i("M104 Invalid extruder "));////MSG_M104_INVALID_EXTRUDER c=0 r=0
|
||||
break;
|
||||
case 105:
|
||||
SERIAL_ECHO(MSG_M105_INVALID_EXTRUDER);
|
||||
SERIAL_ECHO(_i("M105 Invalid extruder "));////MSG_M105_INVALID_EXTRUDER c=0 r=0
|
||||
break;
|
||||
case 109:
|
||||
SERIAL_ECHO(MSG_M109_INVALID_EXTRUDER);
|
||||
SERIAL_ECHO(_i("M109 Invalid extruder "));////MSG_M109_INVALID_EXTRUDER c=0 r=0
|
||||
break;
|
||||
case 218:
|
||||
SERIAL_ECHO(MSG_M218_INVALID_EXTRUDER);
|
||||
SERIAL_ECHO(_i("M218 Invalid extruder "));////MSG_M218_INVALID_EXTRUDER c=0 r=0
|
||||
break;
|
||||
case 221:
|
||||
SERIAL_ECHO(MSG_M221_INVALID_EXTRUDER);
|
||||
SERIAL_ECHO(_i("M221 Invalid extruder "));////MSG_M221_INVALID_EXTRUDER c=0 r=0
|
||||
break;
|
||||
}
|
||||
SERIAL_PROTOCOLLN((int)tmp_extruder);
|
||||
@ -8233,7 +8268,7 @@ void recover_print(uint8_t automatic) {
|
||||
char cmd[30];
|
||||
lcd_update_enable(true);
|
||||
lcd_update(2);
|
||||
lcd_setstatuspgm(MSG_RECOVERING_PRINT);
|
||||
lcd_setstatuspgm(_i("Recovering print "));////MSG_RECOVERING_PRINT c=20 r=1
|
||||
|
||||
recover_machine_state_after_power_panic();
|
||||
|
||||
@ -8424,17 +8459,7 @@ void restore_print_from_eeprom() {
|
||||
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// new save/restore printing
|
||||
|
||||
//extern uint32_t sdpos_atomic;
|
||||
|
||||
bool saved_printing = false;
|
||||
uint32_t saved_sdpos = 0;
|
||||
float saved_pos[4] = {0, 0, 0, 0};
|
||||
// Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min.
|
||||
float saved_feedrate2 = 0;
|
||||
uint8_t saved_active_extruder = 0;
|
||||
bool saved_extruder_under_pressure = false;
|
||||
// save/restore printing
|
||||
|
||||
void stop_and_save_print_to_ram(float z_move, float e_move)
|
||||
{
|
||||
|
@ -94,7 +94,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
||||
if (!dir.open(parent, lfilename, O_READ)) {
|
||||
if (lsAction == LS_SerialPrint) {
|
||||
//SERIAL_ECHO_START();
|
||||
//SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR);
|
||||
//SERIAL_ECHOPGM(_i("Cannot open subdir"));////MSG_SD_CANT_OPEN_SUBDIR c=0 r=0
|
||||
//SERIAL_ECHOLN(lfilename);
|
||||
}
|
||||
}
|
||||
@ -183,23 +183,23 @@ void CardReader::initsd()
|
||||
{
|
||||
//if (!card.init(SPI_HALF_SPEED,SDSS))
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(MSG_SD_INIT_FAIL);
|
||||
SERIAL_ECHOLNRPGM(_i("SD init fail"));////MSG_SD_INIT_FAIL c=0 r=0
|
||||
}
|
||||
else if (!volume.init(&card))
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_SD_VOL_INIT_FAIL);
|
||||
SERIAL_ERRORLNRPGM(_i("volume.init failed"));////MSG_SD_VOL_INIT_FAIL c=0 r=0
|
||||
}
|
||||
else if (!root.openRoot(&volume))
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_SD_OPENROOT_FAIL);
|
||||
SERIAL_ERRORLNRPGM(_i("openRoot failed"));////MSG_SD_OPENROOT_FAIL c=0 r=0
|
||||
}
|
||||
else
|
||||
{
|
||||
cardOK = true;
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(MSG_SD_CARD_OK);
|
||||
SERIAL_ECHOLNRPGM(_i("SD card ok"));////MSG_SD_CARD_OK c=0 r=0
|
||||
}
|
||||
workDir=root;
|
||||
curDir=&root;
|
||||
@ -211,7 +211,7 @@ void CardReader::initsd()
|
||||
/*
|
||||
if(!workDir.openRoot(&volume))
|
||||
{
|
||||
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
|
||||
SERIAL_ECHOLNPGM(_T(MSG_SD_WORKDIR_FAIL));
|
||||
}
|
||||
*/
|
||||
|
||||
@ -221,7 +221,7 @@ void CardReader::setroot()
|
||||
{
|
||||
/*if(!workDir.openRoot(&volume))
|
||||
{
|
||||
SERIAL_ECHOLNPGM(MSG_SD_WORKDIR_FAIL);
|
||||
SERIAL_ECHOLNPGM(_T(MSG_SD_WORKDIR_FAIL));
|
||||
}*/
|
||||
workDir=root;
|
||||
|
||||
@ -360,7 +360,7 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
|
||||
SERIAL_ECHOLN(subdirname);
|
||||
if(!myDir.open(curDir,subdirname,O_READ))
|
||||
{
|
||||
SERIAL_PROTOCOLRPGM(MSG_SD_OPEN_FILE_FAIL);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_SD_OPEN_FILE_FAIL));
|
||||
SERIAL_PROTOCOL(subdirname);
|
||||
SERIAL_PROTOCOLLNPGM(".");
|
||||
return;
|
||||
@ -392,20 +392,20 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
|
||||
if (file.open(curDir, fname, O_READ))
|
||||
{
|
||||
filesize = file.fileSize();
|
||||
SERIAL_PROTOCOLRPGM(MSG_SD_FILE_OPENED);
|
||||
SERIAL_PROTOCOLRPGM(_i("File opened: "));////MSG_SD_FILE_OPENED c=0 r=0
|
||||
SERIAL_PROTOCOL(fname);
|
||||
SERIAL_PROTOCOLRPGM(MSG_SD_SIZE);
|
||||
SERIAL_PROTOCOLRPGM(_n(" Size: "));////MSG_SD_SIZE c=0 r=0
|
||||
SERIAL_PROTOCOLLN(filesize);
|
||||
sdpos = 0;
|
||||
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_SD_FILE_SELECTED);
|
||||
SERIAL_PROTOCOLLNRPGM(_i("File selected"));////MSG_SD_FILE_SELECTED c=0 r=0
|
||||
getfilename(0, fname);
|
||||
lcd_setstatus(longFilename[0] ? longFilename : fname);
|
||||
lcd_setstatus("SD-PRINTING ");
|
||||
}
|
||||
else
|
||||
{
|
||||
SERIAL_PROTOCOLRPGM(MSG_SD_OPEN_FILE_FAIL);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_SD_OPEN_FILE_FAIL));
|
||||
SERIAL_PROTOCOL(fname);
|
||||
SERIAL_PROTOCOLLNPGM(".");
|
||||
}
|
||||
@ -414,14 +414,14 @@ void CardReader::openFile(char* name,bool read, bool replace_current/*=true*/)
|
||||
{ //write
|
||||
if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
|
||||
{
|
||||
SERIAL_PROTOCOLRPGM(MSG_SD_OPEN_FILE_FAIL);
|
||||
SERIAL_PROTOCOLRPGM(_T(MSG_SD_OPEN_FILE_FAIL));
|
||||
SERIAL_PROTOCOL(fname);
|
||||
SERIAL_PROTOCOLLNPGM(".");
|
||||
}
|
||||
else
|
||||
{
|
||||
saving = true;
|
||||
SERIAL_PROTOCOLRPGM(MSG_SD_WRITE_TO_FILE);
|
||||
SERIAL_PROTOCOLRPGM(_i("Writing to file: "));////MSG_SD_WRITE_TO_FILE c=0 r=0
|
||||
SERIAL_PROTOCOLLN(name);
|
||||
lcd_setstatus(fname);
|
||||
}
|
||||
@ -513,7 +513,7 @@ void CardReader::getStatus()
|
||||
if(sdprinting){
|
||||
SERIAL_PROTOCOL(longFilename);
|
||||
SERIAL_PROTOCOLPGM("\n");
|
||||
SERIAL_PROTOCOLRPGM(MSG_SD_PRINTING_BYTE);
|
||||
SERIAL_PROTOCOLRPGM(_i("SD printing byte "));////MSG_SD_PRINTING_BYTE c=0 r=0
|
||||
SERIAL_PROTOCOL(sdpos);
|
||||
SERIAL_PROTOCOLPGM("/");
|
||||
SERIAL_PROTOCOLLN(filesize);
|
||||
@ -523,7 +523,10 @@ void CardReader::getStatus()
|
||||
SERIAL_PROTOCOL(itostr2(time%60));
|
||||
SERIAL_PROTOCOLPGM("\n");
|
||||
}
|
||||
else{
|
||||
else if (saved_printing) {
|
||||
SERIAL_PROTOCOLLNPGM("Print saved");
|
||||
}
|
||||
else {
|
||||
SERIAL_PROTOCOLLNPGM("Not SD printing");
|
||||
}
|
||||
}
|
||||
@ -546,7 +549,7 @@ void CardReader::write_command(char *buf)
|
||||
if (file.writeError)
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_SD_ERR_WRITE_TO_FILE);
|
||||
SERIAL_ERRORLNRPGM(_T(MSG_SD_ERR_WRITE_TO_FILE));
|
||||
}
|
||||
}
|
||||
|
||||
@ -558,7 +561,7 @@ void CardReader::write_command_no_newline(char *buf)
|
||||
if (file.writeError)
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_SD_ERR_WRITE_TO_FILE);
|
||||
SERIAL_ERRORLNRPGM(_T(MSG_SD_ERR_WRITE_TO_FILE));
|
||||
MYSERIAL.println("An error while writing to the SD Card.");
|
||||
}
|
||||
}
|
||||
@ -673,7 +676,7 @@ void CardReader::chdir(const char * relpath)
|
||||
if(!newfile.open(*parent,relpath, O_READ))
|
||||
{
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(MSG_SD_CANT_ENTER_SUBDIR);
|
||||
SERIAL_ECHORPGM(_i("Cannot enter subdir: "));////MSG_SD_CANT_ENTER_SUBDIR c=0 r=0
|
||||
SERIAL_ECHOLN(relpath);
|
||||
}
|
||||
else
|
||||
@ -748,14 +751,14 @@ void CardReader::presort() {
|
||||
// Never sort more than the max allowed
|
||||
// If you use folders to organize, 20 may be enough
|
||||
if (fileCnt > SDSORT_LIMIT) {
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_FILE_CNT);
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."));////MSG_FILE_CNT c=20 r=4
|
||||
fileCnt = SDSORT_LIMIT;
|
||||
}
|
||||
lcd_implementation_clear();
|
||||
#if !SDSORT_USES_RAM
|
||||
lcd_set_progress();
|
||||
#endif
|
||||
lcd_print_at_PGM(0, 1, MSG_SORTING);
|
||||
lcd_print_at_PGM(0, 1, _i("Sorting files"));////MSG_SORTING c=20 r=1
|
||||
|
||||
// Sort order is always needed. May be static or dynamic.
|
||||
#if SDSORT_DYNAMIC_RAM
|
||||
|
@ -286,7 +286,7 @@ void enquecommand(const char *cmd, bool from_progmem)
|
||||
else
|
||||
strcpy(cmdbuffer + bufindw + CMDHDRSIZE, cmd);
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(MSG_Enqueing);
|
||||
SERIAL_ECHORPGM(_T(MSG_Enqueing));
|
||||
SERIAL_ECHO(cmdbuffer + bufindw + CMDHDRSIZE);
|
||||
SERIAL_ECHOLNPGM("\"");
|
||||
bufindw += len + (CMDHDRSIZE + 1);
|
||||
@ -298,7 +298,7 @@ void enquecommand(const char *cmd, bool from_progmem)
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
} else {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ECHORPGM(MSG_Enqueing);
|
||||
SERIAL_ECHORPGM(_T(MSG_Enqueing));
|
||||
if (from_progmem)
|
||||
SERIAL_PROTOCOLRPGM(cmd);
|
||||
else
|
||||
@ -425,7 +425,7 @@ void get_command()
|
||||
// M110 - set current line number.
|
||||
// Line numbers not sent in succession.
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_LINE_NO);
|
||||
SERIAL_ERRORRPGM(_n("Line Number is not Last Line Number+1, Last Line: "));////MSG_ERR_LINE_NO c=0 r=0
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
//Serial.println(gcode_N);
|
||||
FlushSerialRequestResend();
|
||||
@ -441,7 +441,7 @@ void get_command()
|
||||
checksum = checksum^(*p++);
|
||||
if (int(strtol(strchr_pointer+1, NULL, 10)) != int(checksum)) {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_CHECKSUM_MISMATCH);
|
||||
SERIAL_ERRORRPGM(_i("checksum mismatch, Last Line: "));////MSG_ERR_CHECKSUM_MISMATCH c=0 r=0
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
FlushSerialRequestResend();
|
||||
serial_count = 0;
|
||||
@ -453,7 +453,7 @@ void get_command()
|
||||
else
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_NO_CHECKSUM);
|
||||
SERIAL_ERRORRPGM(_i("No Checksum with line number, Last Line: "));////MSG_ERR_NO_CHECKSUM c=0 r=0
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
FlushSerialRequestResend();
|
||||
serial_count = 0;
|
||||
@ -470,7 +470,7 @@ void get_command()
|
||||
{
|
||||
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORRPGM(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM);
|
||||
SERIAL_ERRORRPGM(_n("No Line Number with checksum, Last Line: "));////MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM c=0 r=0
|
||||
SERIAL_ERRORLN(gcode_LastN);
|
||||
serial_count = 0;
|
||||
return;
|
||||
@ -483,8 +483,8 @@ void get_command()
|
||||
if (Stopped == true) {
|
||||
int gcode = strtol(strchr_pointer+1, NULL, 10);
|
||||
if (gcode >= 0 && gcode <= 3) {
|
||||
SERIAL_ERRORLNRPGM(MSG_ERR_STOPPED);
|
||||
LCD_MESSAGERPGM(MSG_STOPPED);
|
||||
SERIAL_ERRORLNRPGM(_T(MSG_ERR_STOPPED));
|
||||
LCD_MESSAGERPGM(_T(MSG_STOPPED));
|
||||
}
|
||||
}
|
||||
} // end of 'G' command
|
||||
@ -580,7 +580,7 @@ void get_command()
|
||||
serial_count >= (MAX_CMD_SIZE - 1) || n==-1)
|
||||
{
|
||||
if(card.eof()){
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_FILE_PRINTED);
|
||||
SERIAL_PROTOCOLLNRPGM(_n("Done printing file"));////MSG_FILE_PRINTED c=0 r=0
|
||||
stoptime=millis();
|
||||
char time[30];
|
||||
unsigned long t=(stoptime-starttime-pause_time)/1000;
|
||||
|
@ -18,4 +18,11 @@
|
||||
#define TMC2130_SPCR SPI_SPCR(TMC2130_SPI_RATE, 1, 1, 1, 0)
|
||||
#define TMC2130_SPSR SPI_SPSR(TMC2130_SPI_RATE)
|
||||
|
||||
//LANG - Multi-language support
|
||||
//#define LANG_MODE 0 // primary language only
|
||||
#define LANG_MODE 1 // sec. language support
|
||||
#define LANG_SIZE_RESERVED 0x2700 // reserved space for secondary language (~10kb)
|
||||
//#define LANG_SIZE_RESERVED 0x1ef8 // reserved space for secondary language (~10kb)
|
||||
|
||||
|
||||
#endif //_CONFIG_H
|
||||
|
95
Firmware/language.c
Normal file
95
Firmware/language.c
Normal file
@ -0,0 +1,95 @@
|
||||
//language.c
|
||||
#include "language.h"
|
||||
#include <inttypes.h>
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
|
||||
// Currectly active language selection.
|
||||
unsigned char lang_selected = 0;
|
||||
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
#else //(LANG_MODE == 0)
|
||||
//reserved xx kbytes for secondary language table
|
||||
const char _SEC_LANG[LANG_SIZE_RESERVED] PROGMEM_I2 = "_SEC_LANG";
|
||||
#endif //(LANG_MODE == 0)
|
||||
|
||||
//lang_table_t structure - 16byte header
|
||||
typedef struct
|
||||
{
|
||||
struct
|
||||
{
|
||||
uint32_t magic;
|
||||
uint16_t size;
|
||||
uint16_t count;
|
||||
uint16_t checksum;
|
||||
uint16_t reserved0;
|
||||
uint32_t reserved1;
|
||||
} header;
|
||||
uint16_t table[];
|
||||
} lang_table_t;
|
||||
|
||||
//lang_table pointer
|
||||
lang_table_t* lang_table = 0;
|
||||
|
||||
|
||||
const char* lang_get_translation(const char* s)
|
||||
{
|
||||
if (lang_selected == 0) return s + 2; //primary language selected
|
||||
if (lang_table == 0) return s + 2; //sec. lang table not found
|
||||
uint16_t ui = pgm_read_word(((uint16_t*)s)); //read string id
|
||||
if (ui == 0xffff) return s + 2; //translation not found
|
||||
ui = pgm_read_word(((uint16_t*)(((char*)lang_table + 16 + ui*2)))); //read relative offset
|
||||
if (pgm_read_byte(((uint8_t*)((char*)lang_table + ui))) == 0)
|
||||
return s + 2;//not translated string
|
||||
return (const char*)((char*)lang_table + ui); //return calculated pointer
|
||||
}
|
||||
|
||||
const char* lang_get_sec_lang_str(const char* s)
|
||||
{
|
||||
uint16_t ui = (uint16_t)&_SEC_LANG; //pointer to _SEC_LANG reserved space
|
||||
ui += 0x00ff; //add 1 page
|
||||
ui &= 0xff00; //align to page
|
||||
lang_table_t* _lang_table = ui; //table pointer
|
||||
ui = pgm_read_word(((uint16_t*)s)); //read string id
|
||||
if (ui == 0xffff) return s + 2; //translation not found
|
||||
ui = pgm_read_word(((uint16_t*)(((char*)_lang_table + 16 + ui*2)))); //read relative offset
|
||||
return (const char*)((char*)_lang_table + ui); //return calculated pointer
|
||||
}
|
||||
|
||||
const char* lang_select(unsigned char lang)
|
||||
{
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
return 0;
|
||||
#else //(LANG_MODE == 0)
|
||||
if (lang == 0) //primary language
|
||||
{
|
||||
lang_table = 0;
|
||||
lang_selected = 0;
|
||||
return;
|
||||
}
|
||||
uint16_t ui = (uint16_t)&_SEC_LANG; //pointer to _SEC_LANG reserved space
|
||||
ui += 0x00ff; //add 1 page
|
||||
ui &= 0xff00; //align to page
|
||||
lang_table = ui; //set table pointer
|
||||
ui = pgm_read_word(((uint16_t*)(((char*)lang_table + 16)))); //read relative offset of first string (language name)
|
||||
return (const char*)((char*)lang_table + ui); //return calculated pointer
|
||||
#endif //(LANG_MODE == 0)
|
||||
}
|
||||
|
||||
unsigned char lang_get_count()
|
||||
{
|
||||
uint16_t ui = (uint16_t)&_SEC_LANG; //pointer to _SEC_LANG reserved space
|
||||
ui += 0x00ff; //add 1 page
|
||||
ui &= 0xff00; //align to page
|
||||
lang_table_t* _lang_table = ui; //table pointer
|
||||
if (pgm_read_dword(((uint32_t*)(_lang_table + 0))) == 0x4bb45aa5) return 2;
|
||||
return 1;
|
||||
}
|
||||
|
||||
const char* lang_get_name(unsigned char lang)
|
||||
{
|
||||
if (lang == 0) return MSG_LANGUAGE_NAME + 2;
|
||||
return lang_get_sec_lang_str(MSG_LANGUAGE_NAME);
|
||||
}
|
||||
|
||||
const char MSG_LANGUAGE_NAME[] PROGMEM_I1 = ISTR("English"); ////c=0 r=0
|
@ -1,6 +1,9 @@
|
||||
//language.h
|
||||
#ifndef LANGUAGE_H
|
||||
#define LANGUAGE_H
|
||||
|
||||
#include "config.h"
|
||||
|
||||
#define PROTOCOL_VERSION "1.0"
|
||||
|
||||
#ifdef CUSTOM_MENDEL_NAME
|
||||
@ -9,8 +12,6 @@
|
||||
#define MACHINE_NAME "Mendel"
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
#ifndef MACHINE_UUID
|
||||
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
#endif
|
||||
@ -20,14 +21,72 @@
|
||||
#define STRINGIFY_(n) #n
|
||||
#define STRINGIFY(n) STRINGIFY_(n)
|
||||
|
||||
//section progmem0 will be used for localized translated strings
|
||||
#define PROGMEM_I2 __attribute__((section(".progmem0")))
|
||||
//section progmem1 will be used for localized strings in english
|
||||
#define PROGMEM_I1 __attribute__((section(".progmem1")))
|
||||
//section progmem2 will be used for not localized strings in english
|
||||
#define PROGMEM_N1 __attribute__((section(".progmem2")))
|
||||
|
||||
// Common serial messages
|
||||
#define MSG_MARLIN "Marlin"
|
||||
|
||||
// Serial Console Messages (do not translate those!)
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
#define _I(s) (__extension__({static const char __c[] PROGMEM_I1 = s; &__c[0];}))
|
||||
#define ISTR(s) s
|
||||
#define _i(s) _I(s)
|
||||
#define _T(s) s
|
||||
#else //(LANG_MODE == 0)
|
||||
#define _I(s) (__extension__({static const char __c[] PROGMEM_I1 = "\xff\xff"s; &__c[0];}))
|
||||
#define ISTR(s) "\xff\xff"s
|
||||
#define _i(s) lang_get_translation(_I(s))
|
||||
#define _T(s) lang_get_translation(s)
|
||||
#endif //(LANG_MODE == 0)
|
||||
#define _N(s) (__extension__({static const char __c[] PROGMEM_N1 = s; &__c[0];}))
|
||||
#define _n(s) _N(s)
|
||||
|
||||
|
||||
// LCD Menu Messages
|
||||
#include "language_all.h"
|
||||
// Language indices into their particular symbol tables.
|
||||
#define LANG_ID_PRI 0
|
||||
#define LANG_ID_SEC 1
|
||||
|
||||
// Language is not defined and it shall be selected from the menu.
|
||||
#define LANG_ID_FORCE_SELECTION 254
|
||||
// Language is not defined on a virgin RAMBo board.
|
||||
#define LANG_ID_UNDEFINED 255
|
||||
|
||||
// Default language ID, if no language is selected.
|
||||
#define LANG_ID_DEFAULT LANG_ID_PRI
|
||||
|
||||
// Number of languages available in the language table.
|
||||
#define LANG_NUM 2
|
||||
|
||||
|
||||
#if defined(__cplusplus)
|
||||
extern "C" {
|
||||
#endif //defined(__cplusplus)
|
||||
|
||||
// Currectly active language selection.
|
||||
extern unsigned char lang_selected;
|
||||
|
||||
#if (LANG_MODE != 0)
|
||||
extern const char _SEC_LANG[LANG_SIZE_RESERVED];
|
||||
#endif //(LANG_MODE == 0)
|
||||
|
||||
extern const char* lang_get_translation(const char* s);
|
||||
extern const char* lang_get_sec_lang_str(const char* s);
|
||||
extern const char* lang_select(unsigned char lang);
|
||||
extern unsigned char lang_get_count();
|
||||
extern const char* lang_get_name(unsigned char lang);
|
||||
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif //defined(__cplusplus)
|
||||
|
||||
#define CAT2(_s1, _s2) _s1
|
||||
#define CAT4(_s1, _s2, _s3, _s4) _s1
|
||||
|
||||
extern const char MSG_LANGUAGE_NAME[];
|
||||
|
||||
#include "messages.h"
|
||||
|
||||
|
||||
#endif //__LANGUAGE_H
|
||||
|
||||
|
@ -2193,7 +2193,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
#endif // SUPPORT_VERBOSITY
|
||||
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
|
||||
uint8_t next_line;
|
||||
lcd_display_message_fullscreen_P(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1, next_line);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1), next_line);
|
||||
if (next_line > 3)
|
||||
next_line = 3;
|
||||
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
|
||||
@ -2205,10 +2205,10 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
refresh_cmd_timeout();
|
||||
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
|
||||
lcd_implementation_print_at(0, next_line, k + 1);
|
||||
lcd_printPGM(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2);
|
||||
lcd_printPGM(_T(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2));
|
||||
|
||||
if (iteration > 0) {
|
||||
lcd_print_at_PGM(0, next_line + 1, MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION);
|
||||
lcd_print_at_PGM(0, next_line + 1, _i("Iteration "));////MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION c=20 r=0
|
||||
lcd_implementation_print(int(iteration + 1));
|
||||
}
|
||||
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
|
||||
@ -2466,7 +2466,7 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
|
||||
|
||||
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
|
||||
uint8_t next_line;
|
||||
lcd_display_message_fullscreen_P(MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1, next_line);
|
||||
lcd_display_message_fullscreen_P(_i("Improving bed calibration point"), next_line);////MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 c=60 r=0
|
||||
if (next_line > 3)
|
||||
next_line = 3;
|
||||
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
|
||||
@ -2479,7 +2479,7 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
|
||||
// Print the decrasing ID of the measurement point.
|
||||
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
|
||||
lcd_implementation_print_at(0, next_line, mesh_point+1);
|
||||
lcd_printPGM(MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2);
|
||||
lcd_printPGM(_i(" of 4"));////MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14 r=0
|
||||
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
|
||||
|
||||
// Move up.
|
||||
@ -2736,7 +2736,7 @@ bool sample_z() {
|
||||
go_to_current(homing_feedrate[Z_AXIS] / 60);
|
||||
//plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate, active_extruder););
|
||||
|
||||
lcd_show_fullscreen_message_and_wait_P(MSG_PLACE_STEEL_SHEET);
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_PLACE_STEEL_SHEET));
|
||||
|
||||
// Sample Z heights for the mesh bed leveling.
|
||||
// In addition, store the results into an eeprom, to be used later for verification of the bed leveling process.
|
||||
@ -2778,12 +2778,12 @@ bool sample_mesh_and_store_reference()
|
||||
|
||||
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
|
||||
uint8_t next_line;
|
||||
lcd_display_message_fullscreen_P(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1, next_line);
|
||||
lcd_display_message_fullscreen_P(_T(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1), next_line);
|
||||
if (next_line > 3)
|
||||
next_line = 3;
|
||||
// display "point xx of yy"
|
||||
lcd_implementation_print_at(0, next_line, 1);
|
||||
lcd_printPGM(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2);
|
||||
lcd_printPGM(_T(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2));
|
||||
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
|
||||
|
||||
// Sample Z heights for the mesh bed leveling.
|
||||
@ -2803,7 +2803,7 @@ bool sample_mesh_and_store_reference()
|
||||
#ifdef TMC2130
|
||||
if (!axis_known_position[Z_AXIS] && (READ(Z_TMC2130_DIAG) != 0)) //Z crash
|
||||
{
|
||||
kill(MSG_BED_LEVELING_FAILED_POINT_LOW);
|
||||
kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
|
||||
return false;
|
||||
}
|
||||
#endif //TMC2130
|
||||
@ -2811,7 +2811,7 @@ bool sample_mesh_and_store_reference()
|
||||
enable_endstops(false);
|
||||
if (!find_bed_induction_sensor_point_z()) //Z crash or deviation > 50um
|
||||
{
|
||||
kill(MSG_BED_LEVELING_FAILED_POINT_LOW);
|
||||
kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
|
||||
return false;
|
||||
}
|
||||
mbl.set_z(0, 0, current_position[Z_AXIS]);
|
||||
@ -2829,11 +2829,11 @@ bool sample_mesh_and_store_reference()
|
||||
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
|
||||
// display "point xx of yy"
|
||||
lcd_implementation_print_at(0, next_line, mesh_point+1);
|
||||
lcd_printPGM(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2);
|
||||
lcd_printPGM(_T(MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2));
|
||||
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
|
||||
if (!find_bed_induction_sensor_point_z()) //Z crash or deviation > 50um
|
||||
{
|
||||
kill(MSG_BED_LEVELING_FAILED_POINT_LOW);
|
||||
kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
|
||||
return false;
|
||||
}
|
||||
// Get cords of measuring point
|
||||
|
120
Firmware/messages.c
Normal file
120
Firmware/messages.c
Normal file
@ -0,0 +1,120 @@
|
||||
//messages.c
|
||||
#include "language.h"
|
||||
|
||||
//this is because we need include Configuration_prusa.h (CUSTOM_MENDEL_NAME)
|
||||
#define bool char
|
||||
#define true 1
|
||||
#define false 0
|
||||
#include "Configuration_prusa.h"
|
||||
|
||||
//internationalized messages
|
||||
const char MSG_ALL[] PROGMEM_I1 = ISTR("All"); ////c=19 r=1
|
||||
const char MSG_AUTO_HOME[] PROGMEM_I1 = ISTR("Auto home"); ////c=0 r=0
|
||||
const char MSG_AUTO_MODE_ON[] PROGMEM_I1 = ISTR("Mode [auto power]"); ////c=0 r=0
|
||||
const char MSG_BABYSTEP_Z[] PROGMEM_I1 = ISTR("Live adjust Z"); ////c=0 r=0
|
||||
const char MSG_BABYSTEP_Z_NOT_SET[] PROGMEM_I1 = ISTR("Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."); ////c=20 r=12
|
||||
const char MSG_BED[] PROGMEM_I1 = ISTR("Bed"); ////c=0 r=0
|
||||
const char MSG_BED_DONE[] PROGMEM_I1 = ISTR("Bed done"); ////c=0 r=0
|
||||
const char MSG_BED_HEATING[] PROGMEM_I1 = ISTR("Bed Heating"); ////c=0 r=0
|
||||
const char MSG_BED_LEVELING_FAILED_POINT_LOW[] PROGMEM_I1 = ISTR("Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."); ////c=20 r=4
|
||||
const char MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED[] PROGMEM_I1 = ISTR("XYZ calibration failed. Please consult the manual."); ////c=20 r=8
|
||||
const char MSG_CALIBRATE_Z_AUTO[] PROGMEM_I1 = ISTR("Calibrating Z"); ////c=20 r=2
|
||||
const char MSG_CARD_MENU[] PROGMEM_I1 = ISTR("Print from SD"); ////c=0 r=0
|
||||
const char MSG_CONFIRM_NOZZLE_CLEAN[] PROGMEM_I1 = ISTR("Please clean the nozzle for calibration. Click when done."); ////c=20 r=8
|
||||
const char MSG_COOLDOWN[] PROGMEM_I1 = ISTR("Cooldown"); ////c=0 r=0
|
||||
const char MSG_CRASH_DETECTED[] PROGMEM_I1 = ISTR("Crash detected."); ////c=20 r=1
|
||||
const char MSG_CRASHDETECT_NA[] PROGMEM_I1 = ISTR("Crash det. [N/A]"); ////c=0 r=0
|
||||
const char MSG_CRASHDETECT_OFF[] PROGMEM_I1 = ISTR("Crash det. [off]"); ////c=0 r=0
|
||||
const char MSG_CRASHDETECT_ON[] PROGMEM_I1 = ISTR("Crash det. [on]"); ////c=0 r=0
|
||||
const char MSG_ENDSTOP_HIT[] PROGMEM_I1 = ISTR("TRIGGERED"); ////c=0 r=0
|
||||
const char MSG_ENDSTOP_OPEN[] PROGMEM_I1 = ISTR("open"); ////c=0 r=0
|
||||
const char MSG_ENDSTOPS_HIT[] PROGMEM_I1 = ISTR("endstops hit: "); ////c=0 r=0
|
||||
const char MSG_Enqueing[] PROGMEM_I1 = ISTR("enqueing \""); ////c=0 r=0
|
||||
const char MSG_ERR_STOPPED[] PROGMEM_I1 = ISTR("Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"); ////c=0 r=0
|
||||
const char MSG_ERROR[] PROGMEM_I1 = ISTR("ERROR:"); ////c=0 r=0
|
||||
const char MSG_EXTRUDER[] PROGMEM_I1 = ISTR("Extruder"); ////c=17 r=1
|
||||
const char MSG_FAN_SPEED[] PROGMEM_I1 = ISTR("Fan speed"); ////c=14 r=0
|
||||
const char MSG_FILAMENT_CLEAN[] PROGMEM_I1 = ISTR("Filament extruding & with correct color?"); ////c=20 r=2
|
||||
const char MSG_FILAMENT_LOADING_T0[] PROGMEM_I1 = ISTR("Insert filament into extruder 1. Click when done."); ////c=20 r=4
|
||||
const char MSG_FILAMENT_LOADING_T1[] PROGMEM_I1 = ISTR("Insert filament into extruder 2. Click when done."); ////c=20 r=4
|
||||
const char MSG_FILAMENT_LOADING_T2[] PROGMEM_I1 = ISTR("Insert filament into extruder 3. Click when done."); ////c=20 r=4
|
||||
const char MSG_FILAMENT_LOADING_T3[] PROGMEM_I1 = ISTR("Insert filament into extruder 4. Click when done."); ////c=20 r=4
|
||||
const char MSG_FILAMENTCHANGE[] PROGMEM_I1 = ISTR("Change filament"); ////c=0 r=0
|
||||
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1[] PROGMEM_I1 = ISTR("Searching bed calibration point"); ////c=60 r=0
|
||||
const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE2[] PROGMEM_I1 = ISTR(" of 4"); ////c=14 r=0
|
||||
const char MSG_FINISHING_MOVEMENTS[] PROGMEM_I1 = ISTR("Finishing movements"); ////c=20 r=1
|
||||
const char MSG_FOLLOW_CALIBRATION_FLOW[] PROGMEM_I1 = ISTR("Printer has not been calibrated yet. Please follow the manual, chapter First steps, section Calibration flow."); ////c=20 r=8
|
||||
const char MSG_FSENS_AUTOLOAD_NA[] PROGMEM_I1 = ISTR("F. autoload [N/A]"); ////c=17 r=1
|
||||
const char MSG_FSENSOR_OFF[] PROGMEM_I1 = ISTR("Fil. sensor [off]"); ////c=0 r=0
|
||||
const char MSG_FSENSOR_ON[] PROGMEM_I1 = ISTR("Fil. sensor [on]"); ////c=0 r=0
|
||||
const char MSG_HEATING[] PROGMEM_I1 = ISTR("Heating"); ////c=0 r=0
|
||||
const char MSG_HEATING_COMPLETE[] PROGMEM_I1 = ISTR("Heating done."); ////c=20 r=0
|
||||
const char MSG_HOMEYZ[] PROGMEM_I1 = ISTR("Calibrate Z"); ////c=0 r=0
|
||||
const char MSG_CHOOSE_EXTRUDER[] PROGMEM_I1 = ISTR("Choose extruder:"); ////c=20 r=1
|
||||
const char MSG_LOAD_FILAMENT[] PROGMEM_I1 = ISTR("Load filament"); ////c=17 r=0
|
||||
const char MSG_LOADING_FILAMENT[] PROGMEM_I1 = ISTR("Loading filament"); ////c=20 r=0
|
||||
const char MSG_M117_V2_CALIBRATION[] PROGMEM_I1 = ISTR("M117 First layer cal."); ////c=25 r=1
|
||||
const char MSG_MAIN[] PROGMEM_I1 = ISTR("Main"); ////c=0 r=0
|
||||
const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1[] PROGMEM_I1 = ISTR("Measuring reference height of calibration point"); ////c=60 r=0
|
||||
const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2[] PROGMEM_I1 = ISTR(" of 9"); ////c=14 r=0
|
||||
const char MSG_MENU_CALIBRATION[] PROGMEM_I1 = ISTR("Calibration"); ////c=0 r=0
|
||||
const char MSG_NO[] PROGMEM_I1 = ISTR("No"); ////c=0 r=0
|
||||
const char MSG_NOZZLE[] PROGMEM_I1 = ISTR("Nozzle"); ////c=0 r=0
|
||||
const char MSG_OK[] PROGMEM_I1 = ISTR("ok"); ////c=0 r=0
|
||||
const char MSG_PAPER[] PROGMEM_I1 = ISTR("Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."); ////c=20 r=8
|
||||
const char MSG_PLACE_STEEL_SHEET[] PROGMEM_I1 = ISTR("Please place steel sheet on heatbed."); ////c=20 r=4
|
||||
const char MSG_PLEASE_WAIT[] PROGMEM_I1 = ISTR("Please wait"); ////c=20 r=0
|
||||
const char MSG_POWERUP[] PROGMEM_I1 = ISTR("PowerUp"); ////c=0 r=0
|
||||
const char MSG_PREHEAT_NOZZLE[] PROGMEM_I1 = ISTR("Preheat the nozzle!"); ////c=20 r=0
|
||||
const char MSG_PRESS_TO_UNLOAD[] PROGMEM_I1 = ISTR("Please press the knob to unload filament"); ////c=20 r=4
|
||||
const char MSG_PRINT_ABORTED[] PROGMEM_I1 = ISTR("Print aborted"); ////c=20 r=0
|
||||
const char MSG_PULL_OUT_FILAMENT[] PROGMEM_I1 = ISTR("Please pull out filament immediately"); ////c=20 r=4
|
||||
const char MSG_RECOVER_PRINT[] PROGMEM_I1 = ISTR("Blackout occurred. Recover print?"); ////c=20 r=2
|
||||
const char MSG_REFRESH[] PROGMEM_I1 = ISTR("\xF8" "Refresh"); ////c=0 r=0
|
||||
const char MSG_REMOVE_STEEL_SHEET[] PROGMEM_I1 = ISTR("Please remove steel sheet from heatbed."); ////c=20 r=4
|
||||
const char MSG_SD_ERR_WRITE_TO_FILE[] PROGMEM_I1 = ISTR("error writing to file"); ////c=0 r=0
|
||||
const char MSG_SD_OPEN_FILE_FAIL[] PROGMEM_I1 = ISTR("open failed, File: "); ////c=0 r=0
|
||||
const char MSG_SD_WORKDIR_FAIL[] PROGMEM_I1 = ISTR("workDir open failed"); ////c=0 r=0
|
||||
const char MSG_SELFTEST_COOLING_FAN[] PROGMEM_I1 = ISTR("Front print fan?"); ////c=20 r=0
|
||||
const char MSG_SELFTEST_EXTRUDER_FAN[] PROGMEM_I1 = ISTR("Left hotend fan?"); ////c=20 r=0
|
||||
const char MSG_SELFTEST_FAILED[] PROGMEM_I1 = ISTR("Selftest failed "); ////c=20 r=0
|
||||
const char MSG_SELFTEST_FAN[] PROGMEM_I1 = ISTR("Fan test"); ////c=20 r=0
|
||||
const char MSG_SELFTEST_FAN_NO[] PROGMEM_I1 = ISTR("Not spinning"); ////c=19 r=0
|
||||
const char MSG_SELFTEST_FAN_YES[] PROGMEM_I1 = ISTR("Spinning"); ////c=19 r=0
|
||||
const char MSG_SELFTEST_CHECK_BED[] PROGMEM_I1 = ISTR("Checking bed "); ////c=20 r=0
|
||||
const char MSG_SELFTEST_CHECK_FSENSOR[] PROGMEM_I1 = ISTR("Checking sensors "); ////c=20 r=0
|
||||
const char MSG_SELFTEST_MOTOR[] PROGMEM_I1 = ISTR("Motor"); ////c=0 r=0
|
||||
const char MSG_SELFTEST_WIRINGERROR[] PROGMEM_I1 = ISTR("Wiring error"); ////c=0 r=0
|
||||
const char MSG_SETTINGS[] PROGMEM_I1 = ISTR("Settings"); ////c=0 r=0
|
||||
const char MSG_SILENT_MODE_OFF[] PROGMEM_I1 = ISTR("Mode [high power]"); ////c=0 r=0
|
||||
const char MSG_SILENT_MODE_ON[] PROGMEM_I1 = ISTR("Mode [silent]"); ////c=0 r=0
|
||||
const char MSG_STEALTH_MODE_OFF[] PROGMEM_I1 = ISTR("Mode [Normal]"); ////c=0 r=0
|
||||
const char MSG_STEALTH_MODE_ON[] PROGMEM_I1 = ISTR("Mode [Stealth]"); ////c=0 r=0
|
||||
const char MSG_STEEL_SHEET_CHECK[] PROGMEM_I1 = ISTR("Is steel sheet on heatbed?"); ////c=20 r=2
|
||||
const char MSG_STOP_PRINT[] PROGMEM_I1 = ISTR("Stop print"); ////c=0 r=0
|
||||
const char MSG_STOPPED[] PROGMEM_I1 = ISTR("STOPPED. "); ////c=0 r=0
|
||||
const char MSG_TEMP_CALIBRATION[] PROGMEM_I1 = ISTR("Temp. cal. "); ////c=20 r=1
|
||||
const char MSG_TEMP_CALIBRATION_DONE[] PROGMEM_I1 = ISTR("Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."); ////c=20 r=12
|
||||
const char MSG_UNLOAD_FILAMENT[] PROGMEM_I1 = ISTR("Unload filament"); ////c=17 r=0
|
||||
const char MSG_UNLOADING_FILAMENT[] PROGMEM_I1 = ISTR("Unloading filament"); ////c=20 r=1
|
||||
const char MSG_WATCH[] PROGMEM_I1 = ISTR("Info screen"); ////c=0 r=0
|
||||
const char MSG_WIZARD_CALIBRATION_FAILED[] PROGMEM_I1 = ISTR("Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."); ////c=20 r=8
|
||||
const char MSG_WIZARD_DONE[] PROGMEM_I1 = ISTR("All is done. Happy printing!"); ////c=20 r=8
|
||||
const char MSG_WIZARD_HEATING[] PROGMEM_I1 = ISTR("Preheating nozzle. Please wait."); ////c=20 r=3
|
||||
const char MSG_WIZARD_QUIT[] PROGMEM_I1 = ISTR("You can always resume the Wizard from Calibration -> Wizard."); ////c=20 r=8
|
||||
const char MSG_YES[] PROGMEM_I1 = ISTR("Yes"); ////c=0 r=0
|
||||
const char WELCOME_MSG[] PROGMEM_I1 = ISTR(CUSTOM_MENDEL_NAME " ready."); ////c=20 r=0
|
||||
//not internationalized messages
|
||||
const char MSG_BROWNOUT_RESET[] PROGMEM_N1 = " Brown out Reset"; ////c=0 r=0
|
||||
const char MSG_EXTERNAL_RESET[] PROGMEM_N1 = " External Reset"; ////c=0 r=0
|
||||
const char MSG_FILE_SAVED[] PROGMEM_N1 = "Done saving file."; ////c=0 r=0
|
||||
const char MSG_OFF[] PROGMEM_N1 = "Off"; ////c=0 r=0
|
||||
const char MSG_ON[] PROGMEM_N1 = "On "; ////c=0 r=0
|
||||
const char MSG_POSITION_UNKNOWN[] PROGMEM_N1 = "Home X/Y before Z"; ////c=0 r=0
|
||||
const char MSG_SOFTWARE_RESET[] PROGMEM_N1 = " Software Reset"; ////c=0 r=0
|
||||
const char MSG_UNKNOWN_COMMAND[] PROGMEM_N1 = "Unknown command: \""; ////c=0 r=0
|
||||
const char MSG_WATCHDOG_RESET[] PROGMEM_N1 = " Watchdog Reset"; ////c=0 r=0
|
||||
const char MSG_Z_MAX[] PROGMEM_N1 = "z_max: "; ////c=0 r=0
|
||||
const char MSG_Z_MIN[] PROGMEM_N1 = "z_min: "; ////c=0 r=0
|
||||
const char MSG_ZPROBE_OUT[] PROGMEM_N1 = "Z probe out. bed"; ////c=0 r=0
|
||||
const char MSG_ZPROBE_ZOFFSET[] PROGMEM_N1 = "Z Offset"; ////c=0 r=0
|
117
Firmware/messages.h
Normal file
117
Firmware/messages.h
Normal file
@ -0,0 +1,117 @@
|
||||
//messages.h
|
||||
|
||||
// Common serial messages
|
||||
#define MSG_MARLIN "Marlin"
|
||||
|
||||
// LCD Menu Messages
|
||||
//internationalized messages
|
||||
extern const char MSG_ALL[];
|
||||
extern const char MSG_AUTO_HOME[];
|
||||
extern const char MSG_AUTO_MODE_ON[];
|
||||
extern const char MSG_BABYSTEP_Z[];
|
||||
extern const char MSG_BABYSTEP_Z_NOT_SET[];
|
||||
extern const char MSG_BED[];
|
||||
extern const char MSG_BED_DONE[];
|
||||
extern const char MSG_BED_HEATING[];
|
||||
extern const char MSG_BED_LEVELING_FAILED_POINT_LOW[];
|
||||
extern const char MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED[];
|
||||
extern const char MSG_CALIBRATE_Z_AUTO[];
|
||||
extern const char MSG_CARD_MENU[];
|
||||
extern const char MSG_CONFIRM_NOZZLE_CLEAN[];
|
||||
extern const char MSG_COOLDOWN[];
|
||||
extern const char MSG_CRASH_DETECTED[];
|
||||
extern const char MSG_CRASHDETECT_NA[];
|
||||
extern const char MSG_CRASHDETECT_OFF[];
|
||||
extern const char MSG_CRASHDETECT_ON[];
|
||||
extern const char MSG_ENDSTOP_HIT[];
|
||||
extern const char MSG_ENDSTOP_OPEN[];
|
||||
extern const char MSG_ENDSTOPS_HIT[];
|
||||
extern const char MSG_Enqueing[];
|
||||
extern const char MSG_ERR_STOPPED[];
|
||||
extern const char MSG_ERROR[];
|
||||
extern const char MSG_EXTRUDER[];
|
||||
extern const char MSG_FAN_SPEED[];
|
||||
extern const char MSG_FILAMENT_CLEAN[];
|
||||
extern const char MSG_FILAMENT_LOADING_T0[];
|
||||
extern const char MSG_FILAMENT_LOADING_T1[];
|
||||
extern const char MSG_FILAMENT_LOADING_T2[];
|
||||
extern const char MSG_FILAMENT_LOADING_T3[];
|
||||
extern const char MSG_FILAMENTCHANGE[];
|
||||
extern const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1[];
|
||||
extern const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE2[];
|
||||
extern const char MSG_FINISHING_MOVEMENTS[];
|
||||
extern const char MSG_FOLLOW_CALIBRATION_FLOW[];
|
||||
extern const char MSG_FSENS_AUTOLOAD_NA[];
|
||||
extern const char MSG_FSENSOR_OFF[];
|
||||
extern const char MSG_FSENSOR_ON[];
|
||||
extern const char MSG_HEATING[];
|
||||
extern const char MSG_HEATING_COMPLETE[];
|
||||
extern const char MSG_HOMEYZ[];
|
||||
extern const char MSG_CHOOSE_EXTRUDER[];
|
||||
extern const char MSG_LOAD_FILAMENT[];
|
||||
extern const char MSG_LOADING_FILAMENT[];
|
||||
extern const char MSG_M117_V2_CALIBRATION[];
|
||||
extern const char MSG_MAIN[];
|
||||
extern const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1[];
|
||||
extern const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2[];
|
||||
extern const char MSG_MENU_CALIBRATION[];
|
||||
extern const char MSG_NO[];
|
||||
extern const char MSG_NOZZLE[];
|
||||
extern const char MSG_OK[];
|
||||
extern const char MSG_PAPER[];
|
||||
extern const char MSG_PLACE_STEEL_SHEET[];
|
||||
extern const char MSG_PLEASE_WAIT[];
|
||||
extern const char MSG_POWERUP[];
|
||||
extern const char MSG_PREHEAT_NOZZLE[];
|
||||
extern const char MSG_PRESS_TO_UNLOAD[];
|
||||
extern const char MSG_PRINT_ABORTED[];
|
||||
extern const char MSG_PULL_OUT_FILAMENT[];
|
||||
extern const char MSG_RECOVER_PRINT[];
|
||||
extern const char MSG_REFRESH[];
|
||||
extern const char MSG_REMOVE_STEEL_SHEET[];
|
||||
extern const char MSG_SD_ERR_WRITE_TO_FILE[];
|
||||
extern const char MSG_SD_OPEN_FILE_FAIL[];
|
||||
extern const char MSG_SD_WORKDIR_FAIL[];
|
||||
extern const char MSG_SELFTEST_COOLING_FAN[];
|
||||
extern const char MSG_SELFTEST_EXTRUDER_FAN[];
|
||||
extern const char MSG_SELFTEST_FAILED[];
|
||||
extern const char MSG_SELFTEST_FAN[];
|
||||
extern const char MSG_SELFTEST_FAN_NO[];
|
||||
extern const char MSG_SELFTEST_FAN_YES[];
|
||||
extern const char MSG_SELFTEST_CHECK_BED[];
|
||||
extern const char MSG_SELFTEST_CHECK_FSENSOR[];
|
||||
extern const char MSG_SELFTEST_MOTOR[];
|
||||
extern const char MSG_SELFTEST_WIRINGERROR[];
|
||||
extern const char MSG_SETTINGS[];
|
||||
extern const char MSG_SILENT_MODE_OFF[];
|
||||
extern const char MSG_SILENT_MODE_ON[];
|
||||
extern const char MSG_STEALTH_MODE_OFF[];
|
||||
extern const char MSG_STEALTH_MODE_ON[];
|
||||
extern const char MSG_STEEL_SHEET_CHECK[];
|
||||
extern const char MSG_STOP_PRINT[];
|
||||
extern const char MSG_STOPPED[];
|
||||
extern const char MSG_TEMP_CALIBRATION[];
|
||||
extern const char MSG_TEMP_CALIBRATION_DONE[];
|
||||
extern const char MSG_UNLOAD_FILAMENT[];
|
||||
extern const char MSG_UNLOADING_FILAMENT[];
|
||||
extern const char MSG_WATCH[];
|
||||
extern const char MSG_WIZARD_CALIBRATION_FAILED[];
|
||||
extern const char MSG_WIZARD_DONE[];
|
||||
extern const char MSG_WIZARD_HEATING[];
|
||||
extern const char MSG_WIZARD_QUIT[];
|
||||
extern const char MSG_YES[];
|
||||
extern const char WELCOME_MSG[];
|
||||
//not internationalized messages
|
||||
extern const char MSG_BROWNOUT_RESET[];
|
||||
extern const char MSG_EXTERNAL_RESET[];
|
||||
extern const char MSG_FILE_SAVED[];
|
||||
extern const char MSG_OFF[];
|
||||
extern const char MSG_ON[];
|
||||
extern const char MSG_POSITION_UNKNOWN[];
|
||||
extern const char MSG_SOFTWARE_RESET[];
|
||||
extern const char MSG_UNKNOWN_COMMAND[];
|
||||
extern const char MSG_WATCHDOG_RESET[];
|
||||
extern const char MSG_Z_MAX[];
|
||||
extern const char MSG_Z_MIN[];
|
||||
extern const char MSG_ZPROBE_OUT[];
|
||||
extern const char MSG_ZPROBE_ZOFFSET[];
|
@ -742,7 +742,7 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
||||
de_float = 0;
|
||||
#endif
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(MSG_ERR_COLD_EXTRUDE_STOP);
|
||||
SERIAL_ECHOLNRPGM(_i(" cold extrusion prevented"));////MSG_ERR_COLD_EXTRUDE_STOP c=0 r=0
|
||||
}
|
||||
|
||||
#ifdef PREVENT_LENGTHY_EXTRUDE
|
||||
@ -754,7 +754,7 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
||||
de_float = 0;
|
||||
#endif
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(MSG_ERR_LONG_EXTRUDE_STOP);
|
||||
SERIAL_ECHOLNRPGM(_n(" too long extrusion prevented"));////MSG_ERR_LONG_EXTRUDE_STOP c=0 r=0
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@ -53,7 +53,7 @@ uint8_t sm4_get_dir(uint8_t axis)
|
||||
case 1: return (PORTL & 1)?0:1;
|
||||
case 2: return (PORTL & 4)?0:1;
|
||||
case 3: return (PORTL & 64)?1:0;
|
||||
#else if ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
#elif ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
case 0: return (PORTL & 1)?1:0;
|
||||
case 1: return (PORTL & 2)?0:1;
|
||||
case 2: return (PORTL & 4)?1:0;
|
||||
@ -72,7 +72,7 @@ void sm4_set_dir(uint8_t axis, uint8_t dir)
|
||||
case 1: if (!dir) PORTL |= 1; else PORTL &= ~1; break;
|
||||
case 2: if (!dir) PORTL |= 4; else PORTL &= ~4; break;
|
||||
case 3: if (dir) PORTL |= 64; else PORTL &= ~64; break;
|
||||
#else if ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
#elif ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
case 0: if (dir) PORTL |= 1; else PORTL &= ~1; break;
|
||||
case 1: if (!dir) PORTL |= 2; else PORTL &= ~2; break;
|
||||
case 2: if (dir) PORTL |= 4; else PORTL &= ~4; break;
|
||||
@ -93,7 +93,7 @@ uint8_t sm4_get_dir_bits(void)
|
||||
if (portL & 4) dir_bits |= 4;
|
||||
if (portL & 64) dir_bits |= 8;
|
||||
dir_bits ^= 0x07; //invert XYZ, do not invert E
|
||||
#else if ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
#elif ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
if (portL & 1) dir_bits |= 1;
|
||||
if (portL & 2) dir_bits |= 2;
|
||||
if (portL & 4) dir_bits |= 4;
|
||||
@ -114,7 +114,7 @@ void sm4_set_dir_bits(uint8_t dir_bits)
|
||||
if (dir_bits & 2) portL |= 1; //set Y direction bit
|
||||
if (dir_bits & 4) portL |= 4; //set Z direction bit
|
||||
if (dir_bits & 8) portL |= 64; //set E direction bit
|
||||
#else if ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
#elif ((MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
dir_bits ^= 0x0a; //invert YE, do not invert XZ
|
||||
if (dir_bits & 1) portL |= 1; //set X direction bit
|
||||
if (dir_bits & 2) portL |= 2; //set Y direction bit
|
||||
|
@ -227,18 +227,18 @@ void checkHitEndstops()
|
||||
{
|
||||
if( endstop_x_hit || endstop_y_hit || endstop_z_hit) {
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHORPGM(MSG_ENDSTOPS_HIT);
|
||||
SERIAL_ECHORPGM(_T(MSG_ENDSTOPS_HIT));
|
||||
if(endstop_x_hit) {
|
||||
SERIAL_ECHOPAIR(" X:",(float)endstops_trigsteps[X_AXIS]/axis_steps_per_unit[X_AXIS]);
|
||||
LCD_MESSAGERPGM(CAT2(MSG_ENDSTOPS_HIT, PSTR("X")));
|
||||
LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT), PSTR("X")));
|
||||
}
|
||||
if(endstop_y_hit) {
|
||||
SERIAL_ECHOPAIR(" Y:",(float)endstops_trigsteps[Y_AXIS]/axis_steps_per_unit[Y_AXIS]);
|
||||
LCD_MESSAGERPGM(CAT2(MSG_ENDSTOPS_HIT, PSTR("Y")));
|
||||
LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT), PSTR("Y")));
|
||||
}
|
||||
if(endstop_z_hit) {
|
||||
SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/axis_steps_per_unit[Z_AXIS]);
|
||||
LCD_MESSAGERPGM(CAT2(MSG_ENDSTOPS_HIT,PSTR("Z")));
|
||||
LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT),PSTR("Z")));
|
||||
}
|
||||
SERIAL_ECHOLN("");
|
||||
endstop_x_hit=false;
|
||||
@ -342,7 +342,7 @@ FORCE_INLINE unsigned short calc_timer(uint16_t step_rate) {
|
||||
timer = (unsigned short)pgm_read_word_near(table_address);
|
||||
timer -= (((unsigned short)pgm_read_word_near(table_address+2) * (unsigned char)(step_rate & 0x0007))>>3);
|
||||
}
|
||||
if(timer < 100) { timer = 100; MYSERIAL.print(MSG_STEPPER_TOO_HIGH); MYSERIAL.println(step_rate); }//(20kHz this should never happen)
|
||||
if(timer < 100) { timer = 100; MYSERIAL.print(_i("Steprate too high: ")); MYSERIAL.println(step_rate); }//(20kHz this should never happen)////MSG_STEPPER_TOO_HIGH c=0 r=0
|
||||
return timer;
|
||||
}
|
||||
|
||||
|
@ -214,9 +214,11 @@ void tmc2130_init()
|
||||
tmc2130_sg_cnt[3] = 0;
|
||||
|
||||
#ifdef TMC2130_LINEARITY_CORRECTION
|
||||
// tmc2130_set_wave(X_AXIS, 247, tmc2130_wave_fac[X_AXIS]);
|
||||
// tmc2130_set_wave(Y_AXIS, 247, tmc2130_wave_fac[Y_AXIS]);
|
||||
// tmc2130_set_wave(Z_AXIS, 247, tmc2130_wave_fac[Z_AXIS]);
|
||||
#ifdef TMC2130_LINEARITY_CORRECTION_XYZ
|
||||
tmc2130_set_wave(X_AXIS, 247, tmc2130_wave_fac[X_AXIS]);
|
||||
tmc2130_set_wave(Y_AXIS, 247, tmc2130_wave_fac[Y_AXIS]);
|
||||
tmc2130_set_wave(Z_AXIS, 247, tmc2130_wave_fac[Z_AXIS]);
|
||||
#endif //TMC2130_LINEARITY_CORRECTION_XYZ
|
||||
tmc2130_set_wave(E_AXIS, 247, tmc2130_wave_fac[E_AXIS]);
|
||||
#endif //TMC2130_LINEARITY_CORRECTION
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -934,22 +934,22 @@ if (print_sd_status)
|
||||
{
|
||||
case 1:
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_HEATING);
|
||||
lcd_printPGM(_T(MSG_HEATING));
|
||||
break;
|
||||
case 2:
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_HEATING_COMPLETE);
|
||||
lcd_printPGM(_T(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);
|
||||
lcd_printPGM(_T(MSG_BED_HEATING));
|
||||
break;
|
||||
case 4:
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_BED_DONE);
|
||||
lcd_printPGM(_T(MSG_BED_DONE));
|
||||
heating_status = 0;
|
||||
heating_status_counter = 0;
|
||||
custom_message = false;
|
||||
@ -968,7 +968,7 @@ if (print_sd_status)
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(PSTR(" "));
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_HOMEYZ_PROGRESS);
|
||||
lcd_printPGM(_i("Calibrating Z"));////MSG_HOMEYZ_PROGRESS c=0 r=0
|
||||
lcd_printPGM(PSTR(" : "));
|
||||
lcd.print(custom_message_state-10);
|
||||
}
|
||||
@ -976,8 +976,8 @@ if (print_sd_status)
|
||||
{
|
||||
if (custom_message_state == 3)
|
||||
{
|
||||
lcd_printPGM(WELCOME_MSG);
|
||||
lcd_setstatuspgm(WELCOME_MSG);
|
||||
lcd_printPGM(_T(WELCOME_MSG));
|
||||
lcd_setstatuspgm(_T(WELCOME_MSG));
|
||||
custom_message = false;
|
||||
custom_message_type = 0;
|
||||
}
|
||||
@ -986,7 +986,7 @@ if (print_sd_status)
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(PSTR(" "));
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_HOMEYZ_DONE);
|
||||
lcd_printPGM(_i("Calibration done"));////MSG_HOMEYZ_DONE c=0 r=0
|
||||
custom_message_state--;
|
||||
}
|
||||
}
|
||||
@ -1012,7 +1012,7 @@ if (print_sd_status)
|
||||
if (custom_message_type == 4) {
|
||||
char progress[4];
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_TEMP_CALIBRATION);
|
||||
lcd_printPGM(_T(MSG_TEMP_CALIBRATION));
|
||||
lcd.setCursor(12, 3);
|
||||
sprintf(progress, "%d/6", custom_message_state);
|
||||
lcd.print(progress);
|
||||
@ -1020,7 +1020,7 @@ if (print_sd_status)
|
||||
// temp compensation preheat
|
||||
if (custom_message_type == 5) {
|
||||
lcd.setCursor(0, 3);
|
||||
lcd_printPGM(MSG_PINDA_PREHEAT);
|
||||
lcd_printPGM(_i("PINDA Heating"));////MSG_PINDA_PREHEAT c=20 r=1
|
||||
if (custom_message_state <= PINDA_HEAT_T) {
|
||||
lcd_printPGM(PSTR(": "));
|
||||
lcd.print(custom_message_state); //seconds
|
||||
|
@ -289,11 +289,11 @@ bool show_upgrade_dialog_if_version_newer(const char *version_string)
|
||||
}
|
||||
|
||||
if (upgrade) {
|
||||
lcd_display_message_fullscreen_P(MSG_NEW_FIRMWARE_AVAILABLE);
|
||||
lcd_display_message_fullscreen_P(_i("New firmware version available:"));////MSG_NEW_FIRMWARE_AVAILABLE c=20 r=2
|
||||
lcd_print_at_PGM(0, 2, PSTR(""));
|
||||
for (const char *c = version_string; ! is_whitespace_or_nl_or_eol(*c); ++ c)
|
||||
lcd_implementation_write(*c);
|
||||
lcd_print_at_PGM(0, 3, MSG_NEW_FIRMWARE_PLEASE_UPGRADE);
|
||||
lcd_print_at_PGM(0, 3, _i("Please upgrade."));////MSG_NEW_FIRMWARE_PLEASE_UPGRADE c=20 r=0
|
||||
tone(BEEPER, 1000);
|
||||
delay_keep_alive(50);
|
||||
noTone(BEEPER);
|
||||
|
@ -42,9 +42,9 @@ AXIS SETTINGS
|
||||
|
||||
|
||||
// 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.
|
||||
#define X_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Y_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Z_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
|
||||
// Direction inverting
|
||||
#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true
|
||||
|
@ -42,9 +42,9 @@ AXIS SETTINGS
|
||||
|
||||
|
||||
// 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.
|
||||
#define X_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Y_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Z_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
|
||||
// Direction inverting
|
||||
#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true
|
||||
|
@ -38,9 +38,9 @@
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,133}
|
||||
|
||||
// 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.
|
||||
#define X_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Y_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Z_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
|
||||
// Direction inverting
|
||||
#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true
|
||||
|
@ -38,9 +38,9 @@
|
||||
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,133}
|
||||
|
||||
// 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.
|
||||
#define X_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Y_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Z_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
|
||||
// Direction inverting
|
||||
#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true
|
||||
|
@ -39,9 +39,9 @@
|
||||
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,560}
|
||||
|
||||
// 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.
|
||||
#define X_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Y_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
#define Z_MIN_ENDSTOP_INVERTING 0 // set to true to invert the logic of the endstop.
|
||||
|
||||
// Direction inverting
|
||||
#define INVERT_X_DIR true // for Mendel set to false, for Orca set to true
|
||||
@ -181,6 +181,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
|
||||
|
||||
//#define EXPERIMENTAL_FEATURES
|
||||
#define TMC2130_LINEARITY_CORRECTION
|
||||
#define TMC2130_LINEARITY_CORRECTION_XYZ
|
||||
//#define TMC2130_VARIABLE_RESOLUTION
|
||||
|
||||
|
||||
|
1032
lang/lang_en.txt
Normal file
1032
lang/lang_en.txt
Normal file
File diff suppressed because it is too large
Load Diff
1376
lang/lang_en_cz.txt
Normal file
1376
lang/lang_en_cz.txt
Normal file
File diff suppressed because it is too large
Load Diff
1372
lang/lang_en_de.txt
Normal file
1372
lang/lang_en_de.txt
Normal file
File diff suppressed because it is too large
Load Diff
1372
lang/lang_en_es.txt
Normal file
1372
lang/lang_en_es.txt
Normal file
File diff suppressed because it is too large
Load Diff
1372
lang/lang_en_it.txt
Normal file
1372
lang/lang_en_it.txt
Normal file
File diff suppressed because it is too large
Load Diff
1372
lang/lang_en_pl.txt
Normal file
1372
lang/lang_en_pl.txt
Normal file
File diff suppressed because it is too large
Load Diff
138
lang/make_lang.sh
Normal file
138
lang/make_lang.sh
Normal file
@ -0,0 +1,138 @@
|
||||
#!/bin/sh
|
||||
# makelang.sh - multi-language support high-level script
|
||||
# for generating lang_xx.bin (secondary language binary file)
|
||||
#
|
||||
# Input files:
|
||||
# lang_en.txt
|
||||
# lang_en_$LANG.txt
|
||||
#
|
||||
# Output files:
|
||||
# lang_en.tmp (temporary, will be removed when finished)
|
||||
# lang_en_$LANG.tmp ==||==
|
||||
# lang_en_$LANG.dif ==||==
|
||||
# lang_$LANG.txt
|
||||
#
|
||||
#
|
||||
# Selected language:
|
||||
LANG=$1
|
||||
if [ -z "$LANG" ]; then LANG='cz'; fi
|
||||
#
|
||||
#
|
||||
|
||||
function finish
|
||||
{
|
||||
if [ "$1" == "0" ]; then
|
||||
if [ -e lang_en.tmp ]; then rm lang_en.tmp; fi
|
||||
if [ -e lang_en_$LANG.tmp ]; then rm lang_en_$LANG.tmp; fi
|
||||
if [ -e lang_en_$LANG.dif ]; then rm lang_en_$LANG.dif; fi
|
||||
fi
|
||||
echo
|
||||
if [ "$1" == "0" ]; then
|
||||
echo "make_lang.sh finished with success" >&2
|
||||
else
|
||||
echo "make_lang.sh finished with errors!" >&2
|
||||
fi
|
||||
case "$-" in
|
||||
*i*) echo "press enter key"; read ;;
|
||||
esac
|
||||
exit $1
|
||||
}
|
||||
|
||||
echo "make_lang.sh started" >&2
|
||||
echo "selected language=$LANG" >&2
|
||||
|
||||
#check if input files exists
|
||||
echo -n " checking input files..." >&2
|
||||
if [ ! -e lang_en.txt ]; then echo "NG! file lang_en.txt not found!" >&2; exit 1; fi
|
||||
if [ ! -e lang_en_$LANG.txt ]; then echo "NG! file lang_en_$LANG.txt not found!" >&2; exit 1; fi
|
||||
echo "OK" >&2
|
||||
|
||||
#filter comment and empty lines from key and dictionary files, create temporary files
|
||||
echo -n " creating tmp files..." >&2
|
||||
cat lang_en.txt | sed "/^$/d;/^#/d" > lang_en.tmp
|
||||
cat lang_en_$LANG.txt | sed "/^$/d;/^#/d" > lang_en_$LANG.tmp
|
||||
echo "OK" >&2
|
||||
#cat lang_en_$LANG.tmp | sed 'n;d' >test1.txt
|
||||
|
||||
#compare files using diff and check for differences
|
||||
echo -n " comparing tmp files..." >&2
|
||||
if ! cat lang_en_$LANG.tmp | sed 'n;d' | diff lang_en.tmp - > lang_en_$LANG.dif; then
|
||||
echo "NG!" >&2
|
||||
echo "Entries in lang_en_$LANG.txt are different from lang_en.txt!" >&2
|
||||
echo "please check lang_en_$LANG.dif" >&2
|
||||
finish 1
|
||||
fi
|
||||
echo "OK" >&2
|
||||
|
||||
#generate lang_xx.txt (secondary language text data sorted by ids)
|
||||
echo -n " generating lang_$LANG.txt..." >&2
|
||||
cat lang_en_$LANG.tmp | sed '1~2d' | sed "s/^\"\\\\x00/\"/" > lang_$LANG.txt
|
||||
echo "OK" >&2
|
||||
|
||||
#generate lang_xx.dat (secondary language text data in binary form)
|
||||
echo -n " generating lang_$LANG.dat..." >&2
|
||||
cat lang_$LANG.txt | sed "s/\\\\/\\\\\\\\/g" | while read s; do
|
||||
s=${s#\"}
|
||||
s=${s%\"}
|
||||
echo -n -e "$s"'\x00'
|
||||
done >lang_$LANG.dat
|
||||
echo "OK" >&2
|
||||
|
||||
#calculate variables
|
||||
lt_magic='\xa5\x5a\xb4\x4b'
|
||||
lt_count=$(grep -c '^' lang_$LANG.txt)
|
||||
lt_data_size=$(wc -c lang_$LANG.dat | cut -f1 -d' ')
|
||||
lt_offs_size=$((2 * $lt_count))
|
||||
lt_size=$((16 + $lt_offs_size + $lt_data_size))
|
||||
lt_chsum=1
|
||||
lt_resv0='\xff\xff'
|
||||
lt_resv1='\xff\xff\xff\xff'
|
||||
|
||||
#generate lang_xx.ofs (secondary language text data offset table)
|
||||
echo -n " generating lang_$LANG.ofs..." >&2
|
||||
cat lang_$LANG.txt | sed "s/\\\\x[0-9a-f][0-9a-f]/\./g;s/\\\\[0-7][0-7][0-7]/\./g" |\
|
||||
awk 'BEGIN { o='$((16 + $lt_offs_size))';} { printf("%d\n",o); o+=(length($0)-1); }' > lang_$LANG.ofs
|
||||
echo "OK" >&2
|
||||
|
||||
#generate lang_xx.bin (secondary language result binary file)
|
||||
echo " generating lang_$LANG.bin:" >&2
|
||||
#create empty file
|
||||
dd if=/dev/zero of=lang_$LANG.bin bs=1 count=$lt_size 2>/dev/null
|
||||
#awk code to format ui16 variables for dd
|
||||
awk_ui16='{ h=int($1/256); printf("\\x%02x\\x%02x\n", int($1-256*h), h); }'
|
||||
|
||||
#write data to binary file with dd
|
||||
|
||||
echo -n " writing header (16 bytes)..." >&2
|
||||
echo -n -e "$lt_magic" |\
|
||||
dd of=lang_$LANG.bin bs=1 count=4 seek=0 conv=notrunc 2>/dev/null
|
||||
echo -n -e $(echo -n "$lt_size" | awk "$awk_ui16") |\
|
||||
dd of=lang_$LANG.bin bs=1 count=2 seek=4 conv=notrunc 2>/dev/null
|
||||
echo -n -e $(echo -n "$lt_count" | awk "$awk_ui16") |\
|
||||
dd of=lang_$LANG.bin bs=1 count=2 seek=6 conv=notrunc 2>/dev/null
|
||||
echo -n -e $(echo -n "$lt_chsum" | awk "$awk_ui16") |\
|
||||
dd of=lang_$LANG.bin bs=1 count=2 seek=8 conv=notrunc 2>/dev/null
|
||||
echo -n -e "$lt_resv0" |\
|
||||
dd of=lang_$LANG.bin bs=1 count=2 seek=10 conv=notrunc 2>/dev/null
|
||||
echo -n -e "$lt_resv1" |\
|
||||
dd of=lang_$LANG.bin bs=1 count=4 seek=12 conv=notrunc 2>/dev/null
|
||||
echo "OK" >&2
|
||||
|
||||
echo -n " writing offset table ($lt_offs_size bytes)..." >&2
|
||||
echo -n -e $(cat lang_$LANG.ofs | awk "$awk_ui16" | tr -d '\n'; echo) |\
|
||||
dd of=./lang_$LANG.bin bs=1 count=$lt_offs_size seek=16 conv=notrunc 2>/dev/null
|
||||
echo "OK" >&2
|
||||
|
||||
echo -n " writing text data ($lt_data_size bytes)..." >&2
|
||||
dd if=./lang_$LANG.dat of=./lang_$LANG.bin bs=1 count=$lt_data_size seek=$((16 + $lt_offs_size)) conv=notrunc 2>/dev/null
|
||||
echo "OK" >&2
|
||||
|
||||
echo " lang_table details:" >&2
|
||||
echo " lt_count = $lt_count" >&2
|
||||
echo " lt_size = $lt_size" >&2
|
||||
echo " lt_chsum = $lt_chsum" >&2
|
||||
|
||||
finish 0
|
||||
|
||||
|
||||
|
116
lang/postbuild.sh
Normal file
116
lang/postbuild.sh
Normal file
@ -0,0 +1,116 @@
|
||||
#!/bin/sh
|
||||
# postbuild.sh - multi-language support high-level script
|
||||
# for generating binary with secondary language
|
||||
#
|
||||
# Input files:
|
||||
# $OUTDIR/Firmware.ino.elf
|
||||
# $OUTDIR/sketch/*.o (all object files)
|
||||
#
|
||||
# Output files:
|
||||
# text.sym
|
||||
# $PROGMEM.sym (progmem1.sym)
|
||||
# $PROGMEM.lss (...)
|
||||
# $PROGMEM.hex
|
||||
# $PROGMEM.chr
|
||||
# $PROGMEM.var
|
||||
# $PROGMEM.txt
|
||||
# textaddr.txt
|
||||
#
|
||||
# Output folder and elf file:
|
||||
OUTDIR="../../output"
|
||||
OUTELF="$OUTDIR/Firmware.ino.elf"
|
||||
#
|
||||
# AVR gcc tools used:
|
||||
OBJCOPY=C:/arduino-1.6.8/hardware/tools/avr/bin/avr-objcopy.exe
|
||||
#
|
||||
# Selected language:
|
||||
LANG=$1
|
||||
#if [ -z "$LANG" ]; then LANG='cz'; fi
|
||||
#
|
||||
# Params:
|
||||
IGNORE_MISSING_TEXT=1
|
||||
|
||||
function finish
|
||||
{
|
||||
echo
|
||||
if [ "$1" == "0" ]; then
|
||||
echo "postbuild.sh finished with success" >&2
|
||||
else
|
||||
echo "postbuild.sh finished with errors!" >&2
|
||||
fi
|
||||
case "$-" in
|
||||
*i*) echo "press enter key"; read ;;
|
||||
esac
|
||||
exit $1
|
||||
}
|
||||
|
||||
echo "postbuild.sh started" >&2
|
||||
|
||||
#check input files
|
||||
echo " checking files:" >&2
|
||||
if [ ! -e $OUTDIR ]; then echo " folder '$OUTDIR' not found!" >&2; finish 1; fi
|
||||
echo " folder OK" >&2
|
||||
if [ ! -e $OUTELF ]; then echo " elf file '$OUTELF' not found!" >&2; finish 1; fi
|
||||
echo " elf OK" >&2
|
||||
if ! ls $OUTDIR/sketch/*.o >/dev/null 2>&1; then echo " no object files in '$OUTDIR/sketch/'!" >&2; finish 1; fi
|
||||
echo " objects OK" >&2
|
||||
|
||||
#run progmem.sh - examine content of progmem1
|
||||
echo -n " running progmem.sh..." >&2
|
||||
./progmem.sh 1 2>progmem.out
|
||||
if [ $? -ne 0 ]; then echo "NG! - check progmem.out file" >&2; finish 1; fi
|
||||
echo "OK" >&2
|
||||
|
||||
#run textaddr.sh - map progmem addreses to text identifiers
|
||||
echo -n " running textaddr.sh..." >&2
|
||||
./textaddr.sh 2>textaddr.out
|
||||
if [ $? -ne 0 ]; then echo "NG! - check progmem.out file" >&2; finish 1; fi
|
||||
echo "OK" >&2
|
||||
|
||||
#check for messages declared in progmem1, but not found in lang_en.txt
|
||||
echo -n " checking textaddr.txt..." >&2
|
||||
if cat textaddr.txt | grep "^ADDR NF" >/dev/null; then
|
||||
echo "NG! - some texts not found in lang_en.txt!"
|
||||
if [ $(("0$IGNORE_MISSING_TEXT")) -eq 0 ]; then
|
||||
finish 1
|
||||
else
|
||||
echo " missing text ignored!" >&2
|
||||
fi
|
||||
else
|
||||
echo "OK" >&2
|
||||
fi
|
||||
|
||||
#update progmem1 id entries in binary file
|
||||
echo -n " extracting binary..." >&2
|
||||
$OBJCOPY -I ihex -O binary $OUTDIR/Firmware.ino.hex ./firmware.bin
|
||||
echo "OK" >&2
|
||||
|
||||
#update binary file
|
||||
echo " updating binary:" >&2
|
||||
|
||||
#update progmem1 id entries in binary file
|
||||
echo -n " primary language ids..." >&2
|
||||
cat textaddr.txt | grep "^ADDR OK" | cut -f3- -d' ' | sed "s/^0000/0x/" |\
|
||||
awk '{ id = $2 - 1; hi = int(id / 256); lo = int(id - 256 * hi); printf("%d \\\\x%02x\\\\x%02x\n", strtonum($1), lo, hi); }' |\
|
||||
while read addr data; do
|
||||
echo -n -e $data | dd of=./firmware.bin bs=1 count=2 seek=$addr conv=notrunc oflag=nonblock 2>/dev/null
|
||||
done
|
||||
echo "OK" >&2
|
||||
|
||||
#update _SEC_LANG in binary file if language is selected
|
||||
echo -n " secondary language data..." >&2
|
||||
if [ ! -z "$LANG" ]; then
|
||||
./update_lang.sh $LANG 2>./update_lang.out
|
||||
if [ $? -ne 0 ]; then echo "NG! - check update_lang.out file" >&2; finish 1; fi
|
||||
echo "OK" >&2
|
||||
finish 0
|
||||
else
|
||||
echo "skipped" >&2
|
||||
fi
|
||||
|
||||
#convert bin to hex
|
||||
echo -n " converting to hex..." >&2
|
||||
$OBJCOPY -I binary -O ihex ./firmware.bin ./firmware.hex
|
||||
echo "OK" >&2
|
||||
|
||||
finish 0
|
127
lang/progmem.sh
Normal file
127
lang/progmem.sh
Normal file
@ -0,0 +1,127 @@
|
||||
#!/bin/sh
|
||||
# progmem.sh - multi-language support low-level script
|
||||
# for examining content of progmem sections (default is progmem1)
|
||||
#
|
||||
# Input files:
|
||||
# $OUTDIR/Firmware.ino.elf
|
||||
# $OUTDIR/sketch/*.o (all object files)
|
||||
#
|
||||
# Output files:
|
||||
# text.sym
|
||||
# $PROGMEM.sym
|
||||
# $PROGMEM.lss
|
||||
# $PROGMEM.hex
|
||||
# $PROGMEM.chr
|
||||
# $PROGMEM.var
|
||||
# $PROGMEM.txt
|
||||
#
|
||||
# Program memory used
|
||||
PROGMEM=progmem$1
|
||||
if [ -z "$1" ]; then PROGMEM=progmem1; fi
|
||||
#
|
||||
# Output folder and elf file:
|
||||
OUTDIR="../../output"
|
||||
OUTELF="$OUTDIR/Firmware.ino.elf"
|
||||
#
|
||||
# AVR gcc tools used:
|
||||
OBJDUMP=C:/arduino-1.6.8/hardware/tools/avr/bin/avr-objdump.exe
|
||||
#
|
||||
#
|
||||
# Description of process:
|
||||
# 0. check input files
|
||||
# 1. remove output files
|
||||
# 2. list symbol table of section '.text' from output elf file to text.sym (sorted by address)
|
||||
# 3. list symbol table of section '.$PROGMEM' from all output object files to $PROGMEM.sym
|
||||
# 4. filter only $PROGMEM symbols from text.sym and store it back to $PROGMEM.sym with absolute address
|
||||
# 5. calculate start and stop address of section '.$PROGMEM'
|
||||
# 6. extract string data from elf file to $PROGMEM.hex
|
||||
# 7. prepare string data for character check and conversion (output to $PROGMEM.chr)
|
||||
# 8. perform character check and conversion (output to $PROGMEM.var and $PROGMEM.txt)
|
||||
#
|
||||
|
||||
echo "progmem.sh started" >&2
|
||||
|
||||
# (0)
|
||||
echo " progmem.sh (0) - checking input files" >&2
|
||||
if [ ! -e $OUTDIR ]; then echo "progmem.sh - file '$OUTELF' not found!" >&2; exit 1; fi
|
||||
|
||||
# (1)
|
||||
echo " progmem.sh (1) - removing output files" >&2
|
||||
#remove output files if exists
|
||||
if [ -e text.sym ]; then rm text.sym; fi
|
||||
if [ -e $PROGMEM.sym ]; then rm $PROGMEM.sym; fi
|
||||
if [ -e $PROGMEM.lss ]; then rm $PROGMEM.lss; fi
|
||||
if [ -e $PROGMEM.hex ]; then rm $PROGMEM.hex; fi
|
||||
if [ -e $PROGMEM.chr ]; then rm $PROGMEM.chr; fi
|
||||
if [ -e $PROGMEM.var ]; then rm $PROGMEM.var; fi
|
||||
if [ -e $PROGMEM.txt ]; then rm $PROGMEM.txt; fi
|
||||
|
||||
# (2)
|
||||
echo " progmem.sh (2) - listing symbol table of section '.text'" >&2
|
||||
#list symbols from section '.text' into file text.sym (only address, size and name)
|
||||
$OBJDUMP -t -j ".text" $OUTELF | tail -n +5 | grep -E "^[0-9a-f]{8} [gl] O" | cut -c1-9,28-36,37- | sed "/^$/d" | sort >> text.sym
|
||||
|
||||
# (3)
|
||||
echo " progmem.sh (3) - listing symbol table of section '.$PROGMEM'" >&2
|
||||
#loop over all object files
|
||||
ls "$OUTDIR"/sketch/*.o | while read fn; do
|
||||
echo " processing $fn" >&2
|
||||
#list symbols from section $PROGMEM (only address, size and name)
|
||||
$OBJDUMP -t -j ".$PROGMEM" $fn 2>/dev/null | tail -n +5 | cut -c1-9,28-36,37- | sed "/^$/d" | sort >> $PROGMEM.sym
|
||||
done
|
||||
|
||||
# (4)
|
||||
echo " progmem.sh (4) - filtering $PROGMEM symbols" >&2
|
||||
#create list of $PROGMEM symbol names separated by '\|'
|
||||
progmem=$(cut -c19- $PROGMEM.sym)
|
||||
progmem=$(echo $progmem | sed "s/ /\\\b\\\|\\\b/g")
|
||||
progmem='\b'$progmem'\b'
|
||||
#filter $PROGMEM symbols from section '.text' (result file will contain list sorted by absolute address)
|
||||
cat text.sym | grep $progmem > $PROGMEM.sym
|
||||
|
||||
# (5)
|
||||
echo " progmem.sh (5) - calculating start and stop address" >&2
|
||||
#calculate start addres of section ".$PROGMEM"
|
||||
PROGMEM_BEG=$(head -n1 $PROGMEM.sym | while read offs size name; do echo "0x"$offs; done)
|
||||
#calculate stop addres of section ".$PROGMEM"
|
||||
PROGMEM_END=$(tail -n1 $PROGMEM.sym | while read offs size name; do printf "0x%x" $(("0x"$offs + "0x"$size)); done)
|
||||
echo " START address = "$PROGMEM_BEG >&2
|
||||
echo " STOP address = "$PROGMEM_END >&2
|
||||
|
||||
# (6)
|
||||
echo " progmem.sh (6) - extracting string data from elf" >&2
|
||||
#dump $PROGMEM data in hex format, cut textual data (keep hex data only)
|
||||
$OBJDUMP -d -j ".text" -w -z --start-address=$PROGMEM_BEG --stop-address=$PROGMEM_END $OUTELF | cut -c1-57 > $PROGMEM.lss
|
||||
#convert $PROGMEM.lss to $PROGMEM.hex:
|
||||
# replace empty lines with '|' (variables separated by empty lines)
|
||||
# remove address from multiline variables (keep address at first variable line only)
|
||||
# remove '<' and '>:', remove whitespace at end of lines
|
||||
# remove line-endings, replace separator with '\n' (join hex data lines - each line will contain single variable)
|
||||
# filter progmem symbols
|
||||
cat $PROGMEM.lss | tail -n +7 | sed -E 's/^$/|/;s/^........:\t/ /;s/<//g;s/>:/ /g;s/[ \t]*$//' |\
|
||||
tr -d '\n' | sed "s/[|]/\n/g" | grep $progmem > $PROGMEM.hex
|
||||
|
||||
# (7)
|
||||
echo " progmem.sh (7) - preparing string data" >&2
|
||||
#convert $PROGMEM.hex to $PROGMEM.chr (prepare string data for character check and conversion)
|
||||
# replace first space with tab
|
||||
# replace second space with tab and space
|
||||
# replace all remaining spaces with '\x'
|
||||
# replace all tabs with spaces
|
||||
cat $PROGMEM.hex | sed 's/ /\t/;s/ /\t /;s/ /\\x/g;s/\t/ /g' > $PROGMEM.chr
|
||||
|
||||
# (8)
|
||||
#convert $PROGMEM.chr to $PROGMEM.var (convert data to text)
|
||||
echo " progmem.sh (8) - converting string data" >&2
|
||||
cat $PROGMEM.chr | \
|
||||
sed 's/ \\xff\\xff/ /;' | \
|
||||
sed 's/\\x22/\\\\\\x22/g;' | \
|
||||
sed 's/\\x1b/\\\\\\x1b/g;' | \
|
||||
sed 's/\\x01/\\\\\\x01/g;' | \
|
||||
sed 's/\\xf8/\\\\\\xf8/g;' | \
|
||||
sed 's/\\x00$/\\x0a/;s/^/printf "/;s/$/"/' | sh > $PROGMEM.var
|
||||
cat $PROGMEM.var | sed 's/\r/\n/g' |sed -E 's/^[0-9a-f]{8} [^ ]* //' >$PROGMEM.txt
|
||||
|
||||
echo "progmem.sh finished" >&2
|
||||
|
||||
exit 0
|
48
lang/readme.txt
Normal file
48
lang/readme.txt
Normal file
@ -0,0 +1,48 @@
|
||||
Nova podpora vice jazyku ve firmware
|
||||
|
||||
|
||||
Zmeny oproti stavajicimu frameworku:
|
||||
1. Deklarace lokalizovanych textu primo v kodu, neni nutne udrzovat tabulky.
|
||||
2. Zatim dvoj jazycna verze (en_cz, en_de atd). Moznost rozsirit na vicejazycnou (en_cz_de - pro MK2).
|
||||
3. Moznost vyberu druheho jazyka ulozeneho v SPI flash (nebude zabirat misto v interni flash, pouze MK3).
|
||||
5. Bash postbuild proces namisto perloveho skriptu + nastroje na spravu slovniku.
|
||||
|
||||
Popis:
|
||||
Novy framework je trochu podobny jako znamy i18n20, ale sity na miru pro AVR atmega s ohledem na maximalni jednoduchost a usporu interni flashe.
|
||||
Stringy ktere maji byt prelozene se deklaruji pomoci specialnich maker, zbytek obstara postbuild.
|
||||
Vsechny lokalizovane texty se nachazi ve specialni sekci, v pripade AVR musi byt stringy umisteny v dolnich 64kB flash - tzv 'progmem'.
|
||||
Po zbuildovani arduinem bude fungovat pouze anglictina, je treba spustit postbuild ktery na zaklade slovniku doplni data sekundarniho jazka a vytvori modifikovany hexfile.
|
||||
Jedina data ktera je treba udrzovat jsou slovniky pro preklad. Jsou to textove soubory kde je vzdy sparovan anglicky text s prelozenym textem.
|
||||
Kazdy text ve slovniku je jeden radek, muze obsahovat specialni znaky v hexadecimalni podobe (e.g. '\x0a'). Nasledujici radek je vzdy prelozeny text.
|
||||
Tento jednoduchy format je zvolen proto aby bylo mozno slovniky a proces prekladu spravovat jen pomoci gitu a nekolika skriptu.
|
||||
|
||||
Pokud pridame nebo zmenime nejaky text v kodu, zmeni se po zbuildovani a spusteni nastroje 'update.sh' soubor lang_en_code.txt.
|
||||
To je generovany soubor ktery obsahuje vsechny lokalizovane texty pouzite v kodu setridene podle abecedy.
|
||||
V gitu uvidime zmenu kterou rucne preneseme do slovniku lang_en_xx.txt, zaroven vytvorime pozadavek na preklad ci korekturu pozadovaneho textu.
|
||||
Pokud pridame nebo zmenime nejaky text ve slovnikach, zmeni se po spusteni nastroje 'update.sh' soubor lang_en_dict.txt.
|
||||
Ten obsahuje vsechny lokalizovane texty ze slovniku (v anglictine), respektive mnozinu jejich sjednoceni.
|
||||
V idealnim pripade by soubory lang_en_code.txt a lang_en_dict.txt mely byt totozne.
|
||||
Pokud se zmeni slovnik, je treba znovu vygenerovat binarni soubory lang_en_xx.bin.
|
||||
|
||||
|
||||
Pouziti v kodu, priklady:
|
||||
|
||||
1. deklarace lokalizovaneho textu v kodu - makro '_i':
|
||||
puts_P(_i("Kill all humans!")); //v cz vypise "Zabit vsechny lidi!"
|
||||
|
||||
2. deklarace lokalizovaneho textu jako globalni konstanty - makro 'PROGMEM_I1' a 'ISTR':
|
||||
const char MSG_PREHEAT[] PROGMEM_I1 = ISTR("Preheat"); //deklarace
|
||||
puts_P(get_translation(MSG_PREHEAT)); //v cz vypise "Predehrev"
|
||||
|
||||
3. fukce get_translation - zkratka makro '_T':
|
||||
puts_P(_T(MSG_PREHEAT)); //v cz vypise "Predehrev"
|
||||
|
||||
4. deklarace lokalizovaneho textu jako lokalni promenne - makro '_I':
|
||||
const char* text = preheat?_I("Preheat"):_I("Cooldown");
|
||||
puts_P(_T(text)); //v cz vypise "Predehrev" nebo "Zchlazeni"
|
||||
|
||||
5. deklarace nelokalizovaneho textu - makro 'PROGMEM_N1' a '_n' nebo '_N':
|
||||
const char MSG_MK3[] PROGMEM_N1 = "MK3"; //deklarace
|
||||
const char* text = _n("MK3");
|
||||
nebo
|
||||
const char* text = _N("MK3");
|
68
lang/textaddr.sh
Normal file
68
lang/textaddr.sh
Normal file
@ -0,0 +1,68 @@
|
||||
#!/bin/sh
|
||||
# textaddr.sh - multi-language support low level script
|
||||
# for compiling progmem1.var and lang_en.txt files
|
||||
# to textaddr.txt file (mapping of progmem addreses to text idenifiers)
|
||||
#
|
||||
# Input files:
|
||||
# progmem1.var
|
||||
# lang_en.txt
|
||||
#
|
||||
# Output files:
|
||||
# textaddr.txt
|
||||
#
|
||||
#
|
||||
# Dscription of process:
|
||||
# check if input files exists
|
||||
# create sorted list of strings from progmem1.var and lang_en.txt
|
||||
# lines from progmem1.var will contain addres (8 chars) and english text
|
||||
# lines from lang_en.txt will contain linenumber and english text
|
||||
# after sort this will generate pairs of lines (line from progmem1 first)
|
||||
# result of sort is compiled with simple script and stored into file textaddr.txt
|
||||
#
|
||||
|
||||
echo "textaddr.sh started" >&2
|
||||
|
||||
if [ ! -e progmem1.var ]; then echo 'textaddr.sh - file progmem1.var not found!' >&2; exit 1; fi
|
||||
if [ ! -e lang_en.txt ]; then echo 'textaddr.sh - file lang_en.txt not found!' >&2; exit 1; fi
|
||||
addr=''
|
||||
text=''
|
||||
(cat progmem1.var | sed -E "s/^([^ ]*) ([^ ]*) (.*)/\1 \"\3\"/";\
|
||||
cat lang_en.txt | sed "/^$/d;/^#/d" | sed = | sed '{N;s/\n/ /}') |\
|
||||
sort -k2 |\
|
||||
sed "s/\\\/\\\\\\\/g" | while read num txt; do
|
||||
if [ ${#num} -eq 8 ]; then
|
||||
if [ -z "$addr" ]; then
|
||||
addr=$num
|
||||
else
|
||||
if [ "$text" == "$txt" ]; then
|
||||
addr="$addr $num"
|
||||
else
|
||||
echo "ADDR NF $addr $text"
|
||||
addr=$num
|
||||
fi
|
||||
fi
|
||||
text=$txt
|
||||
else
|
||||
if [ -z "$addr" ]; then
|
||||
echo "TEXT NF $num $txt"
|
||||
else
|
||||
if [ "$text" == "$txt" ]; then
|
||||
if [ ${#addr} -eq 8 ]; then
|
||||
echo "ADDR OK $addr $num"
|
||||
else
|
||||
echo "$addr" | sed "s/ /\n/g" | while read ad; do
|
||||
echo "ADDR OK $ad $num"
|
||||
done
|
||||
fi
|
||||
addr=''
|
||||
text=''
|
||||
else
|
||||
echo "TEXT NF $num $txt"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
done > textaddr.txt
|
||||
|
||||
echo "textaddr.sh finished" >&2
|
||||
|
||||
exit 0
|
68
lang/update_lang.sh
Normal file
68
lang/update_lang.sh
Normal file
@ -0,0 +1,68 @@
|
||||
#!/bin/sh
|
||||
# update_lang.sh - multi-language support low level script
|
||||
# for updating secondary language in binary file
|
||||
#
|
||||
# AVR gcc tools used:
|
||||
OBJCOPY=C:/arduino-1.6.8/hardware/tools/avr/bin/avr-objcopy.exe
|
||||
#
|
||||
# Selected language:
|
||||
LANG=$1
|
||||
if [ -z "$LANG" ]; then LANG='cz'; fi
|
||||
#
|
||||
|
||||
function finish
|
||||
{
|
||||
echo
|
||||
if [ "$1" == "0" ]; then
|
||||
echo "update_lang.sh finished with success" >&2
|
||||
else
|
||||
echo "update_lang.sh finished with errors!" >&2
|
||||
fi
|
||||
case "$-" in
|
||||
*i*) echo "press enter key"; read ;;
|
||||
esac
|
||||
exit $1
|
||||
}
|
||||
|
||||
echo "update_lang.sh started" >&2
|
||||
echo "selected language=$LANG" >&2
|
||||
|
||||
echo -n " checking files..." >&2
|
||||
if [ ! -e text.sym ]; then echo "NG! file text.sym not found!" >&2; finish 1; fi
|
||||
if [ ! -e lang_$LANG.bin ]; then echo "NG! file lang_$LANG.bin not found!" >&2; finish 1; fi
|
||||
if [ ! -e firmware.bin ]; then echo "NG! file firmware.bin not found!" >&2; finish 1; fi
|
||||
echo "OK" >&2
|
||||
|
||||
echo -n " checking symbols..." >&2
|
||||
#find symbol _SEC_LANG in section '.text'
|
||||
sec_lang=$(cat text.sym | grep -E "\b_SEC_LANG\b")
|
||||
if [ -z "$sec_lang" ]; then echo "NG!\n symbol _SEC_LANG not found!" >&2; finish 1; fi
|
||||
echo "OK" >&2
|
||||
|
||||
echo " calculating vars:" >&2
|
||||
#get addres and size
|
||||
sec_lang_addr='0x'$(echo $sec_lang | cut -f1 -d' ')
|
||||
sec_lang_size='0x'$(echo $sec_lang | cut -f2 -d' ')
|
||||
echo " sec_lang_addr =$sec_lang_addr" >&2
|
||||
echo " sec_lang_size =$sec_lang_size" >&2
|
||||
#calculate lang_table_addr (aligned to 256byte page)
|
||||
lang_table_addr=$((256*$((($sec_lang_addr + 255) / 256))))
|
||||
printf " lang_table_addr =0x%04x\n" $lang_table_addr >&2
|
||||
#calculate lang_table_size
|
||||
lang_table_size=$((256*$((($sec_lang_size - ($lang_table_addr - $sec_lang_addr))/256))))
|
||||
printf " lang_table_size =0x%04x (=%d bytes)\n" $lang_table_size $lang_table_size >&2
|
||||
|
||||
#get lang_xx.bin file size
|
||||
lang_file_size=$(wc -c lang_$LANG.bin | cut -f1 -d' ')
|
||||
printf " lang_file_size =0x%04x (=%d bytes)\n" $lang_file_size $lang_file_size >&2
|
||||
|
||||
if [ $lang_file_size -gt $lang_table_size ]; then echo "Lanaguage binary file size too big!"; finish 1; fi
|
||||
|
||||
echo "updating 'firmware.bin'..." >&2
|
||||
dd if=lang_$LANG.bin of=firmware.bin bs=1 seek=$lang_table_addr conv=notrunc 2>/dev/null
|
||||
|
||||
#convert bin to hex
|
||||
echo "converting to hex..." >&2
|
||||
$OBJCOPY -I binary -O ihex ./firmware.bin ./firmware.hex
|
||||
|
||||
finish 0
|
0
Firmware/langtool.pl → lang_backup/langtool.pl
Executable file → Normal file
0
Firmware/langtool.pl → lang_backup/langtool.pl
Executable file → Normal file
34
lang_backup/language.h
Normal file
34
lang_backup/language.h
Normal file
@ -0,0 +1,34 @@
|
||||
#ifndef LANGUAGE_H
|
||||
#define LANGUAGE_H
|
||||
|
||||
#define PROTOCOL_VERSION "1.0"
|
||||
|
||||
#ifdef CUSTOM_MENDEL_NAME
|
||||
// #define CUSTOM_MENDEL_NAME CUSTOM_MENDEL_NAME
|
||||
#else
|
||||
#define MACHINE_NAME "Mendel"
|
||||
#endif
|
||||
|
||||
#define _i PSTR
|
||||
#define _n PSTR
|
||||
|
||||
#ifndef MACHINE_UUID
|
||||
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
#endif
|
||||
|
||||
#define MSG_FW_VERSION "Firmware"
|
||||
|
||||
#define STRINGIFY_(n) #n
|
||||
#define STRINGIFY(n) STRINGIFY_(n)
|
||||
|
||||
|
||||
// Common serial messages
|
||||
#define MSG_MARLIN "Marlin"
|
||||
|
||||
// Serial Console Messages (do not translate those!)
|
||||
|
||||
|
||||
// LCD Menu Messages
|
||||
#include "language_all.h"
|
||||
|
||||
#endif //__LANGUAGE_H
|
20
lang_upgrade/!upgrade.sh
Normal file
20
lang_upgrade/!upgrade.sh
Normal file
@ -0,0 +1,20 @@
|
||||
#!/bin/sh
|
||||
# upgrade.sh
|
||||
#
|
||||
|
||||
if [ -e ../lang_backup ]; then
|
||||
echo 'folder ../lang_backup already exist!'
|
||||
else
|
||||
./clean.sh
|
||||
./make_msgs.sh
|
||||
./find_msgs.sh
|
||||
./make_source.sh
|
||||
echo 'backup old files...'
|
||||
mkdir ../lang_backup
|
||||
mv ../Firmware/langtool.* ../lang_backup/
|
||||
mv ../Firmware/language*.* ../lang_backup/
|
||||
echo 'copying new files...'
|
||||
cp ./source/* ../Firmware/
|
||||
echo 'finished'
|
||||
fi
|
||||
read
|
11
lang_upgrade/clean.sh
Normal file
11
lang_upgrade/clean.sh
Normal file
@ -0,0 +1,11 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
|
||||
echo "removing output files"
|
||||
rm msgs*.txt
|
||||
rm make_msgs.out
|
||||
rm replace_*.out
|
||||
rm ./source/*
|
||||
rmdir ./source
|
||||
echo "step0 finished... press key"
|
||||
read
|
47
lang_upgrade/find_msgs.sh
Normal file
47
lang_upgrade/find_msgs.sh
Normal file
@ -0,0 +1,47 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
echo 'find_msgs.sh'
|
||||
|
||||
#list all source files from source folder except *language* files
|
||||
files=$(ls ../Firmware/*.c* | grep -v 'language'; ls ../Firmware/*.h | grep -v 'language'; )
|
||||
|
||||
echo ' processing msgs_en.txt and msgs_common.txt...'
|
||||
#msgs=$(cat msgs_en.txt | cut -f 1 -d' ')
|
||||
msgs=$(cat msgs_en.txt msgs_common.txt | cut -f 1 -d' ')
|
||||
#msgs=$(cat msgs_common.txt | cut -f 1 -d' ')
|
||||
echo "$msgs" | while read msg; do
|
||||
echo -n "$msg "
|
||||
found=$(grep -c -E "\b$msg\b" $files | sed "/:0$/d;s/.*:/+/g")
|
||||
echo $(("0"$found))
|
||||
done | tee msgs_usage.txt_0
|
||||
cat msgs_usage.txt_0 | sort -k2 -n >msgs_usage.txt
|
||||
rm msgs_usage.txt_0
|
||||
|
||||
#list messages that are not used
|
||||
msgs=$(cat msgs_usage.txt | grep " 0$" | cut -f1 -d' ')
|
||||
#make regular expression from the list - replace spaces with '\b|\b' (match whole words)
|
||||
msgs='\b'$(echo $msgs | sed "s/ /\\\b\\\|\\\b/g")'\b'
|
||||
#grep unused messages
|
||||
cat msgs_en.txt | grep "$msgs" > msgs_en_unused.txt
|
||||
cat msgs_common.txt | grep "$msgs" > msgs_common_unused.txt
|
||||
|
||||
#list messages used once
|
||||
msgs=$(cat msgs_usage.txt | grep " 1$" | cut -f1 -d' ')
|
||||
#make regular expression from the list - replace spaces with '\b|\b' (match whole words)
|
||||
msgs='\b'$(echo $msgs | sed "s/ /\\\b\\\|\\\b/g")'\b'
|
||||
#grep unused messages
|
||||
cat msgs_en.txt | grep "$msgs" > msgs_en_used_once.txt
|
||||
cat msgs_common.txt | grep "$msgs" > msgs_common_used_once.txt
|
||||
|
||||
#list messages used once more (exclude unused and used once)
|
||||
msgs=$(cat msgs_usage.txt | grep -v " 0$" | grep -v " 1$" | cut -f1 -d' ')
|
||||
#make regular expression from the list - replace spaces with '\b|\b' (match whole words)
|
||||
msgs='\b'$(echo $msgs | sed "s/ /\\\b\\\|\\\b/g")'\b'
|
||||
#grep unused messages
|
||||
cat msgs_en.txt | grep "$msgs" > msgs_en_used_more.txt
|
||||
cat msgs_common.txt | grep "$msgs" > msgs_common_used_more.txt
|
||||
|
||||
echo "step2 finished... press key"
|
||||
|
||||
read
|
||||
exit
|
96
lang_upgrade/fix_1.out
Normal file
96
lang_upgrade/fix_1.out
Normal file
@ -0,0 +1,96 @@
|
||||
MSG_ALL OK
|
||||
MSG_AUTO_HOME OK
|
||||
MSG_AUTO_MODE_ON OK
|
||||
MSG_BABYSTEP_Z OK
|
||||
MSG_BABYSTEP_Z_NOT_SET OK
|
||||
MSG_BED OK
|
||||
MSG_BED_DONE OK
|
||||
MSG_BED_HEATING OK
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED OK
|
||||
MSG_CALIBRATE_Z_AUTO OK
|
||||
MSG_CARD_MENU OK
|
||||
MSG_CONFIRM_NOZZLE_CLEAN OK
|
||||
MSG_COOLDOWN OK
|
||||
MSG_CRASH_DETECTED OK
|
||||
MSG_CRASHDETECT_NA OK
|
||||
MSG_CRASHDETECT_OFF OK
|
||||
MSG_CRASHDETECT_ON OK
|
||||
MSG_ENDSTOP_HIT OK
|
||||
MSG_ENDSTOP_OPEN OK
|
||||
MSG_ENDSTOPS_HIT OK
|
||||
MSG_Enqueing OK
|
||||
MSG_ERR_STOPPED OK
|
||||
MSG_ERROR OK
|
||||
MSG_EXTRUDER OK
|
||||
MSG_FAN_SPEED OK
|
||||
MSG_FILAMENT_CLEAN OK
|
||||
MSG_FILAMENT_LOADING_T0 OK
|
||||
MSG_FILAMENT_LOADING_T1 OK
|
||||
MSG_FILAMENT_LOADING_T2 OK
|
||||
MSG_FILAMENT_LOADING_T3 OK
|
||||
MSG_FILAMENTCHANGE OK
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 OK
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 OK
|
||||
MSG_FINISHING_MOVEMENTS OK
|
||||
MSG_FOLLOW_CALIBRATION_FLOW OK
|
||||
MSG_FSENS_AUTOLOAD_NA OK
|
||||
MSG_FSENSOR_OFF OK
|
||||
MSG_FSENSOR_ON OK
|
||||
MSG_HEATING OK
|
||||
MSG_HEATING_COMPLETE OK
|
||||
MSG_HOMEYZ OK
|
||||
MSG_CHOOSE_EXTRUDER OK
|
||||
MSG_LOAD_FILAMENT OK
|
||||
MSG_LOADING_FILAMENT OK
|
||||
MSG_M117_V2_CALIBRATION OK
|
||||
MSG_MAIN OK
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 OK
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 OK
|
||||
MSG_MENU_CALIBRATION OK
|
||||
MSG_NO OK
|
||||
MSG_NOZZLE OK
|
||||
MSG_OK OK
|
||||
MSG_PAPER OK
|
||||
MSG_PLACE_STEEL_SHEET OK
|
||||
MSG_PLEASE_WAIT OK
|
||||
MSG_POWERUP OK
|
||||
MSG_PREHEAT_NOZZLE OK
|
||||
MSG_PRESS_TO_UNLOAD OK
|
||||
MSG_PRINT_ABORTED OK
|
||||
MSG_PULL_OUT_FILAMENT OK
|
||||
MSG_RECOVER_PRINT OK
|
||||
MSG_REFRESH OK
|
||||
MSG_REMOVE_STEEL_SHEET OK
|
||||
MSG_SD_ERR_WRITE_TO_FILE OK
|
||||
MSG_SD_OPEN_FILE_FAIL OK
|
||||
MSG_SD_WORKDIR_FAIL OK
|
||||
MSG_SELFTEST_COOLING_FAN OK
|
||||
MSG_SELFTEST_EXTRUDER_FAN OK
|
||||
MSG_SELFTEST_FAILED OK
|
||||
MSG_SELFTEST_FAN OK
|
||||
MSG_SELFTEST_FAN_NO OK
|
||||
MSG_SELFTEST_FAN_YES OK
|
||||
MSG_SELFTEST_CHECK_BED OK
|
||||
MSG_SELFTEST_CHECK_FSENSOR OK
|
||||
MSG_SELFTEST_MOTOR OK
|
||||
MSG_SELFTEST_WIRINGERROR OK
|
||||
MSG_SETTINGS OK
|
||||
MSG_SILENT_MODE_OFF OK
|
||||
MSG_SILENT_MODE_ON OK
|
||||
MSG_STEALTH_MODE_OFF OK
|
||||
MSG_STEALTH_MODE_ON OK
|
||||
MSG_STEEL_SHEET_CHECK OK
|
||||
MSG_STOP_PRINT OK
|
||||
MSG_STOPPED OK
|
||||
MSG_TEMP_CALIBRATION OK
|
||||
MSG_TEMP_CALIBRATION_DONE OK
|
||||
MSG_UNLOAD_FILAMENT OK
|
||||
MSG_UNLOADING_FILAMENT OK
|
||||
MSG_WATCH OK
|
||||
MSG_WIZARD_CALIBRATION_FAILED OK
|
||||
MSG_WIZARD_DONE OK
|
||||
MSG_WIZARD_HEATING OK
|
||||
MSG_WIZARD_QUIT OK
|
||||
MSG_YES OK
|
||||
WELCOME_MSG OK
|
33
lang_upgrade/fix_source_1.sh
Normal file
33
lang_upgrade/fix_source_1.sh
Normal file
@ -0,0 +1,33 @@
|
||||
#!/bin/sh
|
||||
# fix_source_1.sh - replace in code all usage of localized message constant from messages.h as _T(MSG_xxx)
|
||||
|
||||
if [ -e ./source ]; then
|
||||
echo 'folder ./source already exists.'
|
||||
read
|
||||
exit
|
||||
fi
|
||||
|
||||
#create target folder
|
||||
echo 'creating target folder...'
|
||||
mkdir ./source
|
||||
#list all source files except *language* and *messages*
|
||||
files=$(ls ../Firmware/*.c* | grep -v 'language' | grep -v 'messages'; ls ../Firmware/*.h | grep -v 'language' | grep -v 'messages' )
|
||||
echo 'copying files...'
|
||||
cp $files ./source/
|
||||
#list all source files in target folder
|
||||
files=$(ls ./source/*.c*; ls ./source/*.h )
|
||||
|
||||
#replace source - internatinalized messages used once with _i("TEXT")
|
||||
echo 'processing msgs_en_used_once.txt'
|
||||
cat msgs_en_used_more.txt | sed "s/\\\\/\\\\\\\\/g;s/\//\\\\\\\\\//g" | while read name cols rows text; do
|
||||
if sed -i -E "s/\b$name\b/_T\($name\)/g" $files; then
|
||||
echo "$name OK"
|
||||
else
|
||||
echo "$name NG!"
|
||||
fi
|
||||
done | tee fix_1.out
|
||||
|
||||
echo "fix1 finished... press key"
|
||||
|
||||
read
|
||||
exit
|
13
lang_upgrade/make_lang_en.sh
Normal file
13
lang_upgrade/make_lang_en.sh
Normal file
@ -0,0 +1,13 @@
|
||||
#!/bin/sh
|
||||
# make_lang_en.sh - create english dictionary from msgs
|
||||
echo "make_lang_en.sh"
|
||||
cat msgs_en_used_once.txt msgs_en_used_more.txt |\
|
||||
sed "s/[ ]*$//g" |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' |\
|
||||
sort -k4 | sed "s/^/#/;s/ \"/\n\"/;s/\"$/\"\n/" > lang_en.txt
|
||||
echo "finished... press any key"
|
||||
read
|
||||
exit
|
60
lang_upgrade/make_lang_en_cz.sh
Normal file
60
lang_upgrade/make_lang_en_cz.sh
Normal file
@ -0,0 +1,60 @@
|
||||
#!/bin/sh
|
||||
# make_lang_en_cz.sh - create en_cz dictionary from msgs
|
||||
echo "make_lang_en_cz.sh"
|
||||
echo "please wait..."
|
||||
|
||||
cat msgs_en_used_once.txt msgs_en_used_more.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_en_.txt
|
||||
|
||||
cat msgs_cz.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_cz_.txt
|
||||
|
||||
cat lang_en.txt | sed "/^$/d;/^#/d" | sed "s/\\\/\\\\\\\/g" |\
|
||||
while read text; do
|
||||
msg=''
|
||||
msg=$(grep -a -m 1 -h -w -F "$text" msgs_en_.txt)
|
||||
if [ -z "$msg" ]; then
|
||||
echo "#???"
|
||||
echo "$text"
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
name=$(echo $msg | cut -f1 -d' ')
|
||||
cols=$(echo $msg | cut -f2 -d' ')
|
||||
rows=$(echo $msg | cut -f3 -d' ')
|
||||
echo "#$name $cols $rows"
|
||||
echo "$text"
|
||||
msg_cz=$(grep -a -m 1 -h "^$name " msgs_cz_.txt)
|
||||
if [ -z "$msg_cz" ]; then
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
text_cz=$(echo $msg_cz | cut -f2- -d' ')
|
||||
echo "$text_cz"
|
||||
echo
|
||||
fi
|
||||
fi
|
||||
done > lang_en_cz.txt
|
||||
|
||||
rm msgs_en_.txt
|
||||
rm msgs_cz_.txt
|
||||
|
||||
echo "finished... press any key"
|
||||
read
|
||||
exit
|
||||
|
||||
#not found in msgs_cz:
|
||||
# MSG_EXTRUDER_CORRECTION_OFF " [off"
|
||||
# MSG_MEASURED_OFFSET "[0;0] point offset"
|
||||
# MSG_EXTRUDER_CORRECTION "E-correct"
|
||||
# MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
# MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
# MSG_PRINTER_DISCONNECTED "Printer disconnected"
|
||||
# MSG_PRUSA3D "prusa3d.com"
|
||||
# MSG_TEMP_CAL_WARNING "Stable ambient temperature 21-26C is needed a rigid stand is required."
|
60
lang_upgrade/make_lang_en_de.sh
Normal file
60
lang_upgrade/make_lang_en_de.sh
Normal file
@ -0,0 +1,60 @@
|
||||
#!/bin/sh
|
||||
# make_lang_en_de.sh - create en_de dictionary from msgs
|
||||
echo "make_lang_en_de.sh"
|
||||
echo "please wait..."
|
||||
|
||||
cat msgs_en_used_once.txt msgs_en_used_more.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_en_.txt
|
||||
|
||||
cat msgs_de.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_de_.txt
|
||||
|
||||
cat lang_en.txt | sed "/^$/d;/^#/d" | sed "s/\\\/\\\\\\\/g" |\
|
||||
while read text; do
|
||||
msg=''
|
||||
msg=$(grep -a -m 1 -h -w -F "$text" msgs_en_.txt)
|
||||
if [ -z "$msg" ]; then
|
||||
echo "#???"
|
||||
echo "$text"
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
name=$(echo $msg | cut -f1 -d' ')
|
||||
cols=$(echo $msg | cut -f2 -d' ')
|
||||
rows=$(echo $msg | cut -f3 -d' ')
|
||||
echo "#$name $cols $rows"
|
||||
echo "$text"
|
||||
msg_de=$(grep -a -m 1 -h "^$name " msgs_de_.txt)
|
||||
if [ -z "$msg_de" ]; then
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
text_de=$(echo $msg_de | cut -f2- -d' ')
|
||||
echo "$text_de"
|
||||
echo
|
||||
fi
|
||||
fi
|
||||
done > lang_en_de.txt
|
||||
|
||||
rm msgs_en_.txt
|
||||
rm msgs_de_.txt
|
||||
|
||||
echo "finished... press any key"
|
||||
read
|
||||
exit
|
||||
|
||||
#not found in msgs_de:
|
||||
# MSG_EXTRUDER_CORRECTION_OFF " [off"
|
||||
# MSG_MEASURED_OFFSET "[0;0] point offset"
|
||||
# MSG_EXTRUDER_CORRECTION "E-correct"
|
||||
# MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
# MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
# MSG_PRINTER_DISCONNECTED "Printer disconnected"
|
||||
# MSG_PRUSA3D "prusa3d.com"
|
||||
# MSG_TEMP_CAL_WARNING "Stable ambient temperature 21-26C is needed a rigid stand is required."
|
60
lang_upgrade/make_lang_en_es.sh
Normal file
60
lang_upgrade/make_lang_en_es.sh
Normal file
@ -0,0 +1,60 @@
|
||||
#!/bin/sh
|
||||
# make_lang_en_es.sh - create en_es dictionary from msgs
|
||||
echo "make_lang_en_es.sh"
|
||||
echo "please wait..."
|
||||
|
||||
cat msgs_en_used_once.txt msgs_en_used_more.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_en_.txt
|
||||
|
||||
cat msgs_es.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_es_.txt
|
||||
|
||||
cat lang_en.txt | sed "/^$/d;/^#/d" | sed "s/\\\/\\\\\\\/g" |\
|
||||
while read text; do
|
||||
msg=''
|
||||
msg=$(grep -a -m 1 -h -w -F "$text" msgs_en_.txt)
|
||||
if [ -z "$msg" ]; then
|
||||
echo "#???"
|
||||
echo "$text"
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
name=$(echo $msg | cut -f1 -d' ')
|
||||
cols=$(echo $msg | cut -f2 -d' ')
|
||||
rows=$(echo $msg | cut -f3 -d' ')
|
||||
echo "#$name $cols $rows"
|
||||
echo "$text"
|
||||
msg_es=$(grep -a -m 1 -h "^$name " msgs_es_.txt)
|
||||
if [ -z "$msg_es" ]; then
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
text_es=$(echo $msg_es | cut -f2- -d' ')
|
||||
echo "$text_es"
|
||||
echo
|
||||
fi
|
||||
fi
|
||||
done > lang_en_es.txt
|
||||
|
||||
rm msgs_en_.txt
|
||||
rm msgs_es_.txt
|
||||
|
||||
echo "finished... press any key"
|
||||
read
|
||||
exit
|
||||
|
||||
#not found in msgs_es:
|
||||
# MSG_EXTRUDER_CORRECTION_OFF " [off"
|
||||
# MSG_MEASURED_OFFSET "[0;0] point offset"
|
||||
# MSG_EXTRUDER_CORRECTION "E-correct"
|
||||
# MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
# MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
# MSG_PRINTER_DISCONNECTED "Printer disconnected"
|
||||
# MSG_PRUSA3D "prusa3d.com"
|
||||
# MSG_TEMP_CAL_WARNING "Stable ambient temperature 21-26C is needed a rigid stand is required."
|
60
lang_upgrade/make_lang_en_it.sh
Normal file
60
lang_upgrade/make_lang_en_it.sh
Normal file
@ -0,0 +1,60 @@
|
||||
#!/bin/sh
|
||||
# make_lang_en_it.sh - create en_it dictionary from msgs
|
||||
echo "make_lang_en_it.sh"
|
||||
echo "please wait..."
|
||||
|
||||
cat msgs_en_used_once.txt msgs_en_used_more.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_en_.txt
|
||||
|
||||
cat msgs_it.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_it_.txt
|
||||
|
||||
cat lang_en.txt | sed "/^$/d;/^#/d" | sed "s/\\\/\\\\\\\/g" |\
|
||||
while read text; do
|
||||
msg=''
|
||||
msg=$(grep -a -m 1 -h -w -F "$text" msgs_en_.txt)
|
||||
if [ -z "$msg" ]; then
|
||||
echo "#???"
|
||||
echo "$text"
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
name=$(echo $msg | cut -f1 -d' ')
|
||||
cols=$(echo $msg | cut -f2 -d' ')
|
||||
rows=$(echo $msg | cut -f3 -d' ')
|
||||
echo "#$name $cols $rows"
|
||||
echo "$text"
|
||||
msg_it=$(grep -a -m 1 -h "^$name " msgs_it_.txt)
|
||||
if [ -z "$msg_it" ]; then
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
text_it=$(echo $msg_it | cut -f2- -d' ')
|
||||
echo "$text_it"
|
||||
echo
|
||||
fi
|
||||
fi
|
||||
done > lang_en_it.txt
|
||||
|
||||
rm msgs_en_.txt
|
||||
rm msgs_it_.txt
|
||||
|
||||
echo "finished... press any key"
|
||||
read
|
||||
exit
|
||||
|
||||
#not found in msgs_it:
|
||||
# MSG_EXTRUDER_CORRECTION_OFF " [off"
|
||||
# MSG_MEASURED_OFFSET "[0;0] point offset"
|
||||
# MSG_EXTRUDER_CORRECTION "E-correct"
|
||||
# MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
# MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
# MSG_PRINTER_DISCONNECTED "Printer disconnected"
|
||||
# MSG_PRUSA3D "prusa3d.com"
|
||||
# MSG_TEMP_CAL_WARNING "Stable ambient temperature 21-26C is needed a rigid stand is required."
|
60
lang_upgrade/make_lang_en_pl.sh
Normal file
60
lang_upgrade/make_lang_en_pl.sh
Normal file
@ -0,0 +1,60 @@
|
||||
#!/bin/sh
|
||||
# make_lang_en_pl.sh - create en_pl dictionary from msgs
|
||||
echo "make_lang_en_pl.sh"
|
||||
echo "please wait..."
|
||||
|
||||
cat msgs_en_used_once.txt msgs_en_used_more.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_en_.txt
|
||||
|
||||
cat msgs_pl.txt |\
|
||||
sed "s/\bCUSTOM_MENDEL_NAME\b/\"Prusa i3 MK3\"/g" |\
|
||||
sed "s/\" \"//g" |\
|
||||
sed 's/\\"/\\x22/g' |\
|
||||
sed 's/\\xF8/\\xf8/g' > msgs_pl_.txt
|
||||
|
||||
cat lang_en.txt | sed "/^$/d;/^#/d" | sed "s/\\\/\\\\\\\/g" |\
|
||||
while read text; do
|
||||
msg=''
|
||||
msg=$(grep -a -m 1 -h -w -F "$text" msgs_en_.txt)
|
||||
if [ -z "$msg" ]; then
|
||||
echo "#???"
|
||||
echo "$text"
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
name=$(echo $msg | cut -f1 -d' ')
|
||||
cols=$(echo $msg | cut -f2 -d' ')
|
||||
rows=$(echo $msg | cut -f3 -d' ')
|
||||
echo "#$name $cols $rows"
|
||||
echo "$text"
|
||||
msg_pl=$(grep -a -m 1 -h "^$name " msgs_pl_.txt)
|
||||
if [ -z "$msg_pl" ]; then
|
||||
echo '"\x00"'
|
||||
echo
|
||||
else
|
||||
text_pl=$(echo $msg_pl | cut -f2- -d' ')
|
||||
echo "$text_pl"
|
||||
echo
|
||||
fi
|
||||
fi
|
||||
done > lang_en_pl.txt
|
||||
|
||||
rm msgs_en_.txt
|
||||
rm msgs_pl_.txt
|
||||
|
||||
echo "finished... press any key"
|
||||
read
|
||||
exit
|
||||
|
||||
#not found in msgs_pl:
|
||||
# MSG_EXTRUDER_CORRECTION_OFF " [off"
|
||||
# MSG_MEASURED_OFFSET "[0;0] point offset"
|
||||
# MSG_EXTRUDER_CORRECTION "E-correct"
|
||||
# MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
# MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
# MSG_PRINTER_DISCONNECTED "Printer disconnected"
|
||||
# MSG_PRUSA3D "prusa3d.com"
|
||||
# MSG_TEMP_CAL_WARNING "Stable ambient temperature 21-26C is needed a rigid stand is required."
|
7
lang_upgrade/make_msgs.out
Normal file
7
lang_upgrade/make_msgs.out
Normal file
@ -0,0 +1,7 @@
|
||||
processing language_common.h ...ok (26 messages, 410 characters)
|
||||
processing language_en.h ...ok (373 messages, 9704 characters)
|
||||
processing language_cz.h ...ok (365 messages, 9639 characters)
|
||||
processing language_de.h ...ok (67 messages, 2352 characters)
|
||||
processing language_it.h ...ok (294 messages, 7808 characters)
|
||||
processing language_pl.h ...ok (295 messages, 7308 characters)
|
||||
processing language_es.h ...ok (289 messages, 7516 characters)
|
93
lang_upgrade/make_msgs.sh
Normal file
93
lang_upgrade/make_msgs.sh
Normal file
@ -0,0 +1,93 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
echo 'make_msgs.sh'
|
||||
if [ -e make_msgs.out ]; then rm make_msgs.out; fi
|
||||
CUSTOM_MENDEL_NAME='Prusa i3 MK3'
|
||||
|
||||
calc_charcount()
|
||||
{
|
||||
#extract texts for charcount calculation
|
||||
cat $1 | cut -f$2- -d' ' | sed -E "s/\" \"//g" >_txt.txt_0
|
||||
#replace printer name
|
||||
cat _txt.txt_0 | sed -E "s/CUSTOM_MENDEL_NAME/\"$CUSTOM_MENDEL_NAME\"/g" >_txt.txt_1
|
||||
#replace oct chars with space
|
||||
cat _txt.txt_1 | sed -E "s/\\\\[0-7]{3}/ /g" >_txt.txt_2
|
||||
#replace hex chars with space
|
||||
cat _txt.txt_2 | sed -E "s/\\\\x[0-9A-Fa-f]{2}/ /g" >_txt.txt_3
|
||||
#replace \" with '
|
||||
cat _txt.txt_3 | sed -E "s/\\\\\"/'/g" >_txt.txt_4
|
||||
#replace "_white_space_" with empty sequence - strigs
|
||||
cat _txt.txt_4 | sed -E "s/\"[ \t]*\"//g" >_txt.txt_5
|
||||
#replace " and white space at end of line
|
||||
cat _txt.txt_5 | sed -E "s/\"[ \t]*$/\"/g" >_txt.txt_6
|
||||
#replace all " with empty sequence
|
||||
cat _txt.txt_6 | sed -E "s/\"//g" >_txt.txt_7
|
||||
#calculate charcount
|
||||
stat -c'%s' _txt.txt_7
|
||||
rm _txt.txt_*
|
||||
}
|
||||
|
||||
process_language_common()
|
||||
{
|
||||
echo -n ' processing language_common.h ...' | tee -a make_msgs.out
|
||||
#list all defines without '+' prefix from language_common.h
|
||||
#cat ../Firmware/language_common.h | grep -E "^[+]*define" | sed "s/lenght/length/g" >msgs_common.txt_0
|
||||
cat ../Firmware/language_common.h | grep -E "^define" | sed "s/lenght/length/g" >msgs_common.txt_0
|
||||
#replace define and +define
|
||||
cat msgs_common.txt_0 | sed -E "s/^[+]*define[ \t]*([^ \t]*)[ \t]*([^ \t]*[ \t]*\"[^\"]*\"*)/\1 c=0 r=0 \2/g" | sort >msgs_common.txt
|
||||
#calculate msgcount
|
||||
msgcount=$(grep -c '' msgs_common.txt)
|
||||
#calculate charcount
|
||||
charcount=$(calc_charcount msgs_common.txt 4)
|
||||
#remove tmp files
|
||||
rm msgs_common.txt_*
|
||||
echo "ok ($msgcount messages, $charcount characters)" | tee -a make_msgs.out
|
||||
}
|
||||
|
||||
|
||||
process_language_en()
|
||||
{
|
||||
echo -n ' processing language_en.h ...' | tee -a make_msgs.out
|
||||
#list all defines from language_en.h
|
||||
cat ../Firmware/language_en.h | grep "^#define" | sed "s/lenght/length/g" >msgs_en.txt_0
|
||||
#replace #define(length=xx,lines=xx)
|
||||
cat msgs_en.txt_0 | sed -E "s/^#define\(length=([0-9]*),[ \t]*lines=([0-9]*)\)[ \t]*([^ \t]*)[ \t]*([^ \t]*[ \t]*\"[^\"]*\"*)/\3 c=\1 r=\2 \4/g" >msgs_en.txt_1
|
||||
#replace #define(length=xx)
|
||||
cat msgs_en.txt_1 | sed -E "s/^#define\(length=([0-9]*)\)[ \t]*([^ \t]*)[ \t]*([^ \t]*[ \t]*\"[^\"]*\"*)/\2 c=\1 r=0 \3/g" >msgs_en.txt_2
|
||||
#replace #define
|
||||
cat msgs_en.txt_2 | sed -E "s/^#define[ \t]*([^ \t]*)[ \t]*([^ \t]*[ \t]*\"[^\"]*\"*)/\1 c=0 r=0 \2/g" | sort >msgs_en.txt
|
||||
#calculate msgcount
|
||||
msgcount=$(grep -c '' msgs_en.txt)
|
||||
#calculate charcount
|
||||
charcount=$(calc_charcount msgs_en.txt 4)
|
||||
#remove tmp files
|
||||
rm msgs_en.txt_*
|
||||
echo "ok ($msgcount messages, $charcount characters)" | tee -a make_msgs.out
|
||||
}
|
||||
|
||||
process_language_xx()
|
||||
{
|
||||
echo -n " processing language_$1.h ..." | tee -a make_msgs.out
|
||||
#list all defines from language_cz.h
|
||||
cat "../Firmware/language_$1.h" | grep "^#define" >"msgs_$1.txt_0"
|
||||
cat "msgs_$1.txt_0" | sed -E "s/^#define[ \t]*([^ \t]*)[ \t]*([^ \t]*[ \t]*\"[^\"]*\"*)/\1 \2/g" | sort >"msgs_$1.txt"
|
||||
#calculate msgcount
|
||||
msgcount=$(grep -c '' "msgs_$1.txt")
|
||||
#calculate charcount
|
||||
charcount=$(calc_charcount "msgs_$1.txt" 2)
|
||||
#remove tmp files
|
||||
rm "msgs_$1.txt_0"
|
||||
echo "ok ($msgcount messages, $charcount characters)" | tee -a make_msgs.out
|
||||
}
|
||||
|
||||
process_language_common
|
||||
process_language_en
|
||||
process_language_xx cz
|
||||
process_language_xx de
|
||||
process_language_xx it
|
||||
process_language_xx pl
|
||||
process_language_xx es
|
||||
|
||||
|
||||
echo "step1 finished... press key"
|
||||
read
|
75
lang_upgrade/make_source.sh
Normal file
75
lang_upgrade/make_source.sh
Normal file
@ -0,0 +1,75 @@
|
||||
#!/bin/sh
|
||||
# make_source.sh - step3 - replace old source files and generate new
|
||||
|
||||
|
||||
if [ -e ./source ]; then
|
||||
echo 'folder ./source already exists.'
|
||||
read
|
||||
exit
|
||||
fi
|
||||
|
||||
#create target folder
|
||||
echo 'creating target folder...'
|
||||
mkdir ./source
|
||||
#list all source files except *language*
|
||||
files=$(ls ../Firmware/*.c* | grep -v 'language'; ls ../Firmware/*.h | grep -v 'language' )
|
||||
#copy original source files to target folder
|
||||
echo 'copying files...'
|
||||
cp $files ./source/
|
||||
#list all source files in target folder
|
||||
files=$(ls ./source/*.c*; ls ./source/*.h )
|
||||
|
||||
#replace source - internatinalized messages used once with _i("TEXT")
|
||||
echo 'processing msgs_en_used_once.txt'
|
||||
cat msgs_en_used_once.txt | sed "s/\\\\/\\\\\\\\/g;s/\//\\\\\\\\\//g" | while read name cols rows text; do
|
||||
comment="$name $cols $rows"
|
||||
if sed -i -E "s/(.*)(\b$name\b)(.*)$/\1_i\($text\)\3\/\/\/\/$comment/g" $files; then
|
||||
echo "$name OK"
|
||||
else
|
||||
echo "$name NG!"
|
||||
fi
|
||||
done | tee replace_en.out
|
||||
|
||||
#replace source - not internatinalized messages used once with _n("TEXT")
|
||||
echo 'processing msgs_common_used_once.txt'
|
||||
cat msgs_common_used_once.txt | sed "s/\\\\/\\\\\\\\/g;s/\//\\\\\\\\\//g" | while read name cols rows text; do
|
||||
comment="$name $cols $rows"
|
||||
if sed -i -E "s/(.*)(\b$name\b)(.*)$/\1_n\($text\)\3\/\/\/\/$comment/g" $files; then
|
||||
echo "$name OK"
|
||||
else
|
||||
echo "$name NG!"
|
||||
fi
|
||||
done | tee replace_common.out
|
||||
|
||||
#messages used twice or more will be listed in messages.h and messages.c.
|
||||
cp ./src/messages.h ./source/
|
||||
cp ./src/messages.c ./source/
|
||||
|
||||
echo '//internationalized messages' | tee -a ./source/messages.h >> ./source/messages.c
|
||||
cat msgs_en_used_more.txt | sed 's/\\/\\\\/g' | while read msg cols rows text; do
|
||||
comment="$cols $rows"
|
||||
echo "extern const char $msg[];" >> ./source/messages.h
|
||||
echo "const char $msg[] PROGMEM_I1 = ISTR("$text"); ////$comment" >> ./source/messages.c
|
||||
echo "$msg"
|
||||
done
|
||||
|
||||
echo '//not internationalized messages' | tee -a ./source/messages.h >> ./source/messages.c
|
||||
cat msgs_common_used_more.txt | sed 's/\\/\\\\/g' | while read msg cols rows text; do
|
||||
comment="$cols $rows"
|
||||
echo "extern const char $msg[];" >> ./source/messages.h
|
||||
echo "const char $msg[] PROGMEM_N1 = "$text"; ////$comment" >> ./source/messages.c
|
||||
echo "$msg"
|
||||
done
|
||||
|
||||
|
||||
#copy new source files
|
||||
cp ./src/language.h ./source/
|
||||
cp ./src/language.c ./source/
|
||||
cp ./src/config.h ./source/
|
||||
|
||||
#replace line with declaration in Marlin_main.cpp
|
||||
sed -i -E "s/^(unsigned char lang_selected = 0;)/\/\/\1/" ./source/Marlin_main.cpp
|
||||
|
||||
echo "step3 finished... press key"
|
||||
read
|
||||
exit
|
26
lang_upgrade/msgs_common.txt
Normal file
26
lang_upgrade/msgs_common.txt
Normal file
@ -0,0 +1,26 @@
|
||||
MSG_ACTIVE_EXTRUDER c=0 r=0 "Active Extruder: "
|
||||
MSG_AUTHOR c=0 r=0 " | Author: "
|
||||
MSG_BROWNOUT_RESET c=0 r=0 " Brown out Reset"
|
||||
MSG_COUNT_X c=0 r=0 " Count X: "
|
||||
MSG_ERR_LINE_NO c=0 r=0 "Line Number is not Last Line Number+1, Last Line: "
|
||||
MSG_ERR_LONG_EXTRUDE_STOP c=0 r=0 " too long extrusion prevented"
|
||||
MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM c=0 r=0 "No Line Number with checksum, Last Line: "
|
||||
MSG_EXTERNAL_RESET c=0 r=0 " External Reset"
|
||||
MSG_FILE_PRINTED c=0 r=0 "Done printing file"
|
||||
MSG_FILE_SAVED c=0 r=0 "Done saving file."
|
||||
MSG_INVALID_EXTRUDER c=0 r=0 "Invalid extruder"
|
||||
MSG_OFF c=0 r=0 "Off"
|
||||
MSG_ON c=0 r=0 "On "
|
||||
MSG_POSITION_UNKNOWN c=0 r=0 "Home X/Y before Z"
|
||||
MSG_SD_SIZE c=0 r=0 " Size: "
|
||||
MSG_SOFTWARE_RESET c=0 r=0 " Software Reset"
|
||||
MSG_UNKNOWN_COMMAND c=0 r=0 "Unknown command: \""
|
||||
MSG_WATCHDOG_RESET c=0 r=0 " Watchdog Reset"
|
||||
MSG_X_MAX c=0 r=0 "x_max: "
|
||||
MSG_X_MIN c=0 r=0 "x_min: "
|
||||
MSG_Y_MAX c=0 r=0 "y_max: "
|
||||
MSG_Y_MIN c=0 r=0 "y_min: "
|
||||
MSG_Z_MAX c=0 r=0 "z_max: "
|
||||
MSG_Z_MIN c=0 r=0 "z_min: "
|
||||
MSG_ZPROBE_OUT c=0 r=0 "Z probe out. bed"
|
||||
MSG_ZPROBE_ZOFFSET c=0 r=0 "Z Offset"
|
0
lang_upgrade/msgs_common_unused.txt
Normal file
0
lang_upgrade/msgs_common_unused.txt
Normal file
13
lang_upgrade/msgs_common_used_more.txt
Normal file
13
lang_upgrade/msgs_common_used_more.txt
Normal file
@ -0,0 +1,13 @@
|
||||
MSG_BROWNOUT_RESET c=0 r=0 " Brown out Reset"
|
||||
MSG_EXTERNAL_RESET c=0 r=0 " External Reset"
|
||||
MSG_FILE_SAVED c=0 r=0 "Done saving file."
|
||||
MSG_OFF c=0 r=0 "Off"
|
||||
MSG_ON c=0 r=0 "On "
|
||||
MSG_POSITION_UNKNOWN c=0 r=0 "Home X/Y before Z"
|
||||
MSG_SOFTWARE_RESET c=0 r=0 " Software Reset"
|
||||
MSG_UNKNOWN_COMMAND c=0 r=0 "Unknown command: \""
|
||||
MSG_WATCHDOG_RESET c=0 r=0 " Watchdog Reset"
|
||||
MSG_Z_MAX c=0 r=0 "z_max: "
|
||||
MSG_Z_MIN c=0 r=0 "z_min: "
|
||||
MSG_ZPROBE_OUT c=0 r=0 "Z probe out. bed"
|
||||
MSG_ZPROBE_ZOFFSET c=0 r=0 "Z Offset"
|
13
lang_upgrade/msgs_common_used_once.txt
Normal file
13
lang_upgrade/msgs_common_used_once.txt
Normal file
@ -0,0 +1,13 @@
|
||||
MSG_ACTIVE_EXTRUDER c=0 r=0 "Active Extruder: "
|
||||
MSG_AUTHOR c=0 r=0 " | Author: "
|
||||
MSG_COUNT_X c=0 r=0 " Count X: "
|
||||
MSG_ERR_LINE_NO c=0 r=0 "Line Number is not Last Line Number+1, Last Line: "
|
||||
MSG_ERR_LONG_EXTRUDE_STOP c=0 r=0 " too long extrusion prevented"
|
||||
MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM c=0 r=0 "No Line Number with checksum, Last Line: "
|
||||
MSG_FILE_PRINTED c=0 r=0 "Done printing file"
|
||||
MSG_INVALID_EXTRUDER c=0 r=0 "Invalid extruder"
|
||||
MSG_SD_SIZE c=0 r=0 " Size: "
|
||||
MSG_X_MAX c=0 r=0 "x_max: "
|
||||
MSG_X_MIN c=0 r=0 "x_min: "
|
||||
MSG_Y_MAX c=0 r=0 "y_max: "
|
||||
MSG_Y_MIN c=0 r=0 "y_min: "
|
365
lang_upgrade/msgs_cz.txt
Normal file
365
lang_upgrade/msgs_cz.txt
Normal file
@ -0,0 +1,365 @@
|
||||
MSG_ADJUSTZ "Auto doladit Z ?"
|
||||
MSG_ALL "Vse"
|
||||
MSG_AUTO_HOME "Auto home"
|
||||
MSG_AUTO_MODE_ON "Mod [automaticky]"
|
||||
MSG_AUTOLOAD_FILAMENT "AutoZavedeni fil."
|
||||
MSG_AUTOLOADING_ENABLED "Automaticke zavadeni filamentu aktivni, stisknete tlacitko a vlozte filament..."
|
||||
MSG_AUTOLOADING_ONLY_IF_FSENS_ON "Automaticke zavadeni filamentu dostupne pouze pri zapnutem filament senzoru..."
|
||||
MSG_BABYSTEP_X "Babystep X"
|
||||
MSG_BABYSTEP_Y "Babystep Y"
|
||||
MSG_BABYSTEP_Z "Doladeni osy Z"
|
||||
MSG_BABYSTEP_Z_NOT_SET "Neni zkalibrovana vzdalenost trysky od tiskove podlozky. Postupujte prosim podle manualu, kapitola Zaciname, odstavec Nastaveni prvni vrstvy."
|
||||
MSG_BABYSTEPPING_X "Babystepping X"
|
||||
MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
MSG_BABYSTEPPING_Z "Dostavovani Z"
|
||||
MSG_BED "Bed"
|
||||
MSG_BED_CORRECTION_FRONT "Vpredu [um]"
|
||||
MSG_BED_CORRECTION_LEFT "Vlevo [um]"
|
||||
MSG_BED_CORRECTION_MENU "Korekce podlozky"
|
||||
MSG_BED_CORRECTION_REAR "Vzadu [um]"
|
||||
MSG_BED_CORRECTION_RESET "Reset"
|
||||
MSG_BED_CORRECTION_RIGHT "Vpravo [um]"
|
||||
MSG_BED_DONE "Bed OK."
|
||||
MSG_BED_HEATING "Zahrivani bed"
|
||||
MSG_BED_HEATING_SAFETY_DISABLED "Zahrivani preruseno bezpecnostnim casovacem."
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH "Kalibrace Z selhala. Sensor sepnul prilis vysoko. Cekam na reset."
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW "Kalibrace Z selhala. Sensor nesepnul. Znecistena tryska? Cekam na reset."
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Kalibrace Z selhala. Sensor je odpojeny nebo preruseny kabel. Cekam na reset."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Kalibrace XYZ selhala. Predni kalibracni body moc vpredu. Srovnejte tiskarnu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Kalibrace XYZ selhala. Levy predni bod moc vpredu. Srovnejte tiskarnu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Kalibrace XYZ selhala. Pravy predni bod moc vpredu. Srovnejte tiskarnu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Kalibrace XYZ selhala. Nahlednete do manualu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Kalibrace XYZ v poradku. X/Y osy jsou kolme. Gratuluji!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Kalibrace XYZ selhala. Kalibracni bod podlozky nenalezen."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Kalibrace XYZ v poradku. Zkoseni bude automaticky vyrovnano pri tisku."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Kalibrace XYZ v poradku. X/Y osy mirne zkosene. Dobra prace!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Kalibrace XYZ nepresna. Predni kalibracni body moc vpredu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Kalibrace XYZ nepresna. Levy predni bod moc vpredu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Kalibrace XYZ nepresna. Pravy predni bod moc vpredu."
|
||||
MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
MSG_CALIBRATE_BED "Kalibrace XYZ"
|
||||
MSG_CALIBRATE_BED_RESET "Reset XYZ kalibr."
|
||||
MSG_CALIBRATE_E "Kalibrovat E"
|
||||
MSG_CALIBRATE_PINDA "Zkalibrovat"
|
||||
MSG_CALIBRATE_Z_AUTO "Kalibruji Z"
|
||||
MSG_CALIBRATION_PINDA_MENU "Teplot. kalibrace"
|
||||
MSG_CARD_MENU "Tisk z SD"
|
||||
MSG_CLEAN_NOZZLE_E "E kalibrace ukoncena. Prosim ocistete trysku. Po te potvrdte tlacitkem."
|
||||
MSG_CNG_SDCARD "Vymenit SD"
|
||||
MSG_CONFIGURATION_VER " Last Updated: "
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Dojely oba Z voziky k~hornimu dorazu?"
|
||||
MSG_CONFIRM_NOZZLE_CLEAN "Pro uspesnou kalibraci ocistete prosim tiskovou trysku. Potvrdte tlacitkem."
|
||||
MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamenty jsou srovnany. Pro uspesnou kalibraci prosim ocistete trysku. Po te potvrdte tlacitkem."
|
||||
MSG_CONTROL "Kontrola"
|
||||
MSG_COOLDOWN "Zchladit"
|
||||
MSG_CORRECTLY "Vymena ok?"
|
||||
MSG_CRASH_DET_ONLY_IN_NORMAL "\x1b[2JCrash detekce muze\x1b[1;0Hbyt zapnuta pouze v\x1b[2;0HNormal modu"
|
||||
MSG_CRASH_DET_STEALTH_FORCE_OFF "\x1b[2JPOZOR:\x1b[1;0HCrash detekce\x1b[2;0Hdeaktivovana ve\x1b[3;0HStealth modu"
|
||||
MSG_CRASH_DETECTED "Detekovan naraz."
|
||||
MSG_CRASH_DETECTED2 "Naraz detekovan, pokracovat v tisku?"
|
||||
MSG_CRASHDETECT_NA "Crash det. [N/A]"
|
||||
MSG_CRASHDETECT_OFF "Crash det. [vyp]"
|
||||
MSG_CRASHDETECT_ON "Crash det. [zap]"
|
||||
MSG_CURRENT "Pouze aktualni"
|
||||
MSG_DATE "Datum:"
|
||||
MSG_DEFAULT_SETTINGS_LOADED "Neplatne hodnoty nastaveni. Bude pouzito vychozi PID, Esteps atd."
|
||||
MSG_DISABLE_STEPPERS "Vypnout motory"
|
||||
MSG_DWELL "Sleep..."
|
||||
MSG_E_CAL_KNOB "Otacejte tlacitkem dokud znacka nedosahne tela extruderu. Potvrdte tlacitkem."
|
||||
MSG_END_FILE_LIST "End file list"
|
||||
MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
MSG_ENDSTOP_OPEN "open"
|
||||
MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
MSG_Enqueing "enqueing \""
|
||||
MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
MSG_ERROR "CHYBA:"
|
||||
MSG_EXTRUDER "Extruder"
|
||||
MSG_EXTRUDER_1 "Extruder 1"
|
||||
MSG_EXTRUDER_2 "Extruder 2"
|
||||
MSG_EXTRUDER_3 "Extruder 3"
|
||||
MSG_EXTRUDER_4 "Extruder 4"
|
||||
MSG_FACTOR " \002 Fact"
|
||||
MSG_FAN_SPEED "Rychlost vent."
|
||||
MSG_FANS_CHECK_OFF "Kontr. vent.[vyp]"
|
||||
MSG_FANS_CHECK_ON "Kontr. vent.[zap]"
|
||||
MSG_FIL_ADJUSTING "Probiha srovnani filamentu. Prosim cekejte."
|
||||
MSG_FILAMENT_CLEAN "Filament vytlacen a spravne barvy?"
|
||||
MSG_FILAMENT_LOADING_T0 "Vlozte filament do extruderu 1. Potvrdte tlacitkem."
|
||||
MSG_FILAMENT_LOADING_T1 "Vlozte filament do extruderu 2. Potvrdte tlacitkem."
|
||||
MSG_FILAMENT_LOADING_T2 "Vlozte filament do extruderu 3. Potvrdte tlacitkem."
|
||||
MSG_FILAMENT_LOADING_T3 "Vlozte filament do extruderu 4. Potvrdte tlacitkem."
|
||||
MSG_FILAMENT_SENSOR "Senzor filamentu"
|
||||
MSG_FILAMENTCHANGE "Vymenit filament"
|
||||
MSG_FILE_CNT "Nektere soubory nebudou setrideny. Maximalni pocet souboru pro setrideni je 100."
|
||||
MSG_FILE_INCOMPLETE "Soubor nekompletni. Pokracovat?"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iterace "
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Hledam kalibracni bod podlozky"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
MSG_FINISHING_MOVEMENTS "Dokoncovani pohybu"
|
||||
MSG_FLOW "Prutok"
|
||||
MSG_FLOW0 "Prutok 0"
|
||||
MSG_FLOW1 "Prutok 1"
|
||||
MSG_FLOW2 "Prutok 2"
|
||||
MSG_FOLLOW_CALIBRATION_FLOW "Tiskarna nebyla jeste zkalibrovana. Postupujte prosim podle manualu, kapitola Zaciname, odstavec Postup kalibrace."
|
||||
MSG_FORCE_SELFTEST "Pro kalibraci presneho rehomovani bude nyni spusten selftest."
|
||||
MSG_FREE_MEMORY " Free Memory: "
|
||||
MSG_FSENS_AUTOLOAD_NA "F. autozav. [N/A]"
|
||||
MSG_FSENS_AUTOLOAD_OFF "F. autozav. [vyp]"
|
||||
MSG_FSENS_AUTOLOAD_ON "F. autozav. [zap]"
|
||||
MSG_FSENS_NOT_RESPONDING "CHYBA: Filament senzor nereaguje, zkontrolujte zapojeni."
|
||||
MSG_FSENSOR_NA "Fil. senzor [N/A]"
|
||||
MSG_FSENSOR_OFF "Fil. senzor [vyp]"
|
||||
MSG_FSENSOR_ON "Fil. senzor [zap]"
|
||||
MSG_FW_VERSION_ALPHA "Pouzivate alpha verzi firmwaru. Jedna se o vyvojovou verzi. Pouzivani teto verze firmware neni doporuceno a muze zpusobit poskozeni tiskarny."
|
||||
MSG_FW_VERSION_BETA "Pouzivate beta verzi firmwaru. Jedna se o vyvojovou verzi. Pouzivani teto verze firmware neni doporuceno a muze zpusobit poskozeni tiskarny."
|
||||
MSG_FW_VERSION_RC "Tato verze firmware je release candidate. Nektere z funkci nemusi pracovat spolehlive."
|
||||
MSG_FW_VERSION_UNKNOWN "VAROVANI: Neznama, nepodporovana verze firmware. Pouziti na vlastni nebezpeci!"
|
||||
MSG_HEATING "Zahrivani"
|
||||
MSG_HEATING_COMPLETE "Zahrivani OK."
|
||||
MSG_HOMEYZ "Kalibrovat Z"
|
||||
MSG_HOMEYZ "Kalibrovat Z"
|
||||
MSG_HOMEYZ_DONE "Kalibrace OK"
|
||||
MSG_HOMEYZ_DONE "Kalibrace OK"
|
||||
MSG_HOMEYZ_PROGRESS "Kalibruji Z"
|
||||
MSG_HOMEYZ_PROGRESS "Kalibruji Z"
|
||||
MSG_CHANGE_EXTR "Zmenit extruder"
|
||||
MSG_CHANGE_SUCCESS "Zmena uspesna!"
|
||||
MSG_CHANGED_BOTH "Varovani: doslo ke zmene typu tiskarny a motherboardu."
|
||||
MSG_CHANGED_MOTHERBOARD "Varovani: doslo ke zmene typu motherboardu."
|
||||
MSG_CHANGED_PRINTER "Varovani: doslo ke zmene typu tiskarny."
|
||||
MSG_CHANGING_FILAMENT "Vymena filamentu!"
|
||||
MSG_CHECK_IDLER "Prosim otevrete idler a manualne odstrante filament."
|
||||
MSG_CHOOSE_EXTRUDER "Vyberte extruder:"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Zlepsuji presnost kalibracniho bodu"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
MSG_INFO_EXTRUDER "Extruder info"
|
||||
MSG_INFO_NOZZLE_FAN "Trysk. vent:"
|
||||
MSG_INFO_PRINT_FAN "Tisk. vent:"
|
||||
MSG_INIT_SDCARD "Inic. SD"
|
||||
MSG_INSERT_FILAMENT "Vlozte filament"
|
||||
MSG_KILLED "KILLED. "
|
||||
MSG_LANGUAGE_NAME "Cestina"
|
||||
MSG_LANGUAGE_SELECT "Vyber jazyka"
|
||||
MSG_LEFT "Levy:"
|
||||
MSG_LOAD_ALL "Zavest vse"
|
||||
MSG_LOAD_EPROM "Ulozit pamet"
|
||||
MSG_LOAD_FILAMENT "Zavest filament"
|
||||
MSG_LOAD_FILAMENT_1 "Zavest filament 1"
|
||||
MSG_LOAD_FILAMENT_2 "Zavest filament 2"
|
||||
MSG_LOAD_FILAMENT_3 "Zavest filament 3"
|
||||
MSG_LOAD_FILAMENT_4 "Zavest filament 4"
|
||||
MSG_LOADING_COLOR "Cisteni barvy"
|
||||
MSG_LOADING_FILAMENT "Zavadeni filamentu"
|
||||
MSG_LOOSE_PULLEY "Uvolnena remenicka"
|
||||
MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
MSG_M117_V2_CALIBRATION "M117 Kal. prvni vrstvy"
|
||||
MSG_M119_REPORT "Reporting endstop status"
|
||||
MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
MSG_MAIN "Hlavni nabidka"
|
||||
MSG_MARK_FIL "Oznacte filament 100 mm od tela extruderu a po te potvrdte tlacitkem."
|
||||
MSG_MAX " \002 Max"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Merim referencni vysku kalibracniho bodu"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " z 9"
|
||||
MSG_MEASURED_SKEW "Merene zkoseni:"
|
||||
MSG_MENU_BELT_STATUS "Stav remenu"
|
||||
MSG_MENU_CALIBRATION "Kalibrace"
|
||||
MSG_MENU_TEMPERATURES "Teploty"
|
||||
MSG_MENU_VOLTAGES "Napeti"
|
||||
MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
|
||||
MSG_MIN " \002 Min"
|
||||
MSG_MOTION "Pohyb"
|
||||
MSG_MOVE_AXIS "Posunout osu"
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP "Kalibrace XYZ. Otacenim tlacitka posunte Z osu az k~hornimu dorazu. Potvrdte tlacitkem."
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Kalibrace Z. Otacenim tlacitka posunte Z osu az k~hornimu dorazu. Potvrdte tlacitkem."
|
||||
MSG_MOVE_E "Extruder"
|
||||
MSG_MOVE_X "Posunout X"
|
||||
MSG_MOVE_Y "Posunout Y"
|
||||
MSG_MOVE_Z "Posunout Z"
|
||||
MSG_NEW_FIRMWARE_AVAILABLE "Vysla nova verze firmware:"
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Prosim aktualizujte."
|
||||
MSG_NO "Ne"
|
||||
MSG_NO_CARD "Zadna SD karta"
|
||||
MSG_NO_MOVE "No move."
|
||||
MSG_NOT_COLOR "Barva neni cista"
|
||||
MSG_NOT_LOADED "Filament nezaveden"
|
||||
MSG_NOZZLE "Tryska"
|
||||
MSG_NOZZLE1 "Tryska2"
|
||||
MSG_NOZZLE2 "Tryska3"
|
||||
MSG_OK "ok"
|
||||
MSG_PAPER "Umistete list papiru na podlozku a udrzujte jej pod tryskou behem mereni prvnich 4 bodu. Pokud tryska zachyti papir, vypnete tiskarnu."
|
||||
MSG_PAUSE_PRINT "Pozastavit tisk"
|
||||
MSG_PICK_Z "Vyberte vytisk"
|
||||
MSG_PID_EXTRUDER "PID kalibrace"
|
||||
MSG_PID_FINISHED "PID kal. ukoncena"
|
||||
MSG_PID_RUNNING "PID kal. "
|
||||
MSG_PINDA_NOT_CALIBRATED "Tiskarna nebyla teplotne zkalibrovana"
|
||||
MSG_PINDA_PREHEAT "Nahrivani PINDA"
|
||||
MSG_PLA_FILAMENT_LOADED "Je PLA filament zaveden?"
|
||||
MSG_PLACE_STEEL_SHEET "Umistete prosim tiskovy plat na heatbed"
|
||||
MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
MSG_PLEASE_LOAD_PLA "Nejdrive zavedte PLA filament prosim."
|
||||
MSG_PLEASE_WAIT "Prosim cekejte"
|
||||
MSG_POWERUP "PowerUp"
|
||||
MSG_PREHEAT "Predehrev"
|
||||
MSG_PREHEAT_NOZZLE "Predehrejte trysku!"
|
||||
MSG_PREPARE_FILAMENT "Pripravte filament"
|
||||
MSG_PRESS "a stisknete tlacitko"
|
||||
MSG_PRESS_TO_PREHEAT "Pro nahrati trysky a pokracovani stisknete tlacitko."
|
||||
MSG_PRESS_TO_UNLOAD "Pro vysunuti filamentu stisknete prosim tlacitko"
|
||||
MSG_PRINT_ABORTED "Tisk prerusen"
|
||||
MSG_PRINT_PAUSED "Tisk pozastaven"
|
||||
MSG_PULL_OUT_FILAMENT "Prosim vyjmete urychlene filament"
|
||||
MSG_REBOOT "Restartujte tiskarnu"
|
||||
MSG_RECOVER_PRINT "Detekovan vypadek proudu.Obnovit tisk?"
|
||||
MSG_RECOVERING_PRINT "Obnovovani tisku "
|
||||
MSG_RECTRACT "Rectract"
|
||||
MSG_REFRESH "\xF8" "Obnovit"
|
||||
MSG_REMOVE_STEEL_SHEET "Odstrante tiskovy plat z heatbed prosim."
|
||||
MSG_RESEND "Resend: "
|
||||
MSG_RESTORE_FAILSAFE "Obnovit vychozi"
|
||||
MSG_RESUME_PRINT "Pokracovat"
|
||||
MSG_RESUMING "Obnoveni tisku"
|
||||
MSG_RESUMING_PRINT "Obnovovani tisku"
|
||||
MSG_RIGHT "Pravy:"
|
||||
MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
MSG_SD_CARD_OK "SD card ok"
|
||||
MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
MSG_SD_FILE_OPENED "File opened: "
|
||||
MSG_SD_FILE_SELECTED "File selected"
|
||||
MSG_SD_INIT_FAIL "SD init fail"
|
||||
MSG_SD_INSERTED "Karta vlozena"
|
||||
MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
MSG_SD_REMOVED "Karta vyjmuta"
|
||||
MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
MSG_SECOND_SERIAL_OFF "RPi port [vyp]"
|
||||
MSG_SECOND_SERIAL_ON "RPi port [zap]"
|
||||
MSG_SELFTEST "Selftest "
|
||||
MSG_SELFTEST_AXIS "Osa"
|
||||
MSG_SELFTEST_AXIS_LENGTH "Delka osy"
|
||||
MSG_SELFTEST_BEDHEATER "Bed / Heater"
|
||||
MSG_SELFTEST_COOLING_FAN "Predni tiskovy vent?"
|
||||
MSG_SELFTEST_ENDSTOP "Endstop"
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||
MSG_SELFTEST_ENDSTOPS "Endstops"
|
||||
MSG_SELFTEST_ERROR "Selftest error !"
|
||||
MSG_SELFTEST_EXTRUDER_FAN "Levy vent na trysce?"
|
||||
MSG_SELFTEST_EXTRUDER_FAN_SPEED "Levy vent.:"
|
||||
MSG_SELFTEST_FAILED "Selftest selhal "
|
||||
MSG_SELFTEST_FAN "Test ventilatoru"
|
||||
MSG_SELFTEST_FAN_NO "Netoci se"
|
||||
MSG_SELFTEST_FAN_YES "Toci se"
|
||||
MSG_SELFTEST_FANS "Predni/levy vent."
|
||||
MSG_SELFTEST_FILAMENT_SENSOR "Senzor filamentu:"
|
||||
MSG_SELFTEST_HEATERTHERMISTOR "Heater/Thermistor"
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT "Vse OK "
|
||||
MSG_SELFTEST_CHECK_BED "Kontrola bed "
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS "Kontrola endstops"
|
||||
MSG_SELFTEST_CHECK_FSENSOR "Kontrola senzoru"
|
||||
MSG_SELFTEST_CHECK_HOTEND "Kontrola hotend "
|
||||
MSG_SELFTEST_CHECK_X "Kontrola X axis "
|
||||
MSG_SELFTEST_CHECK_Y "Kontrola Y axis "
|
||||
MSG_SELFTEST_CHECK_Z "Kontrola Z axis "
|
||||
MSG_SELFTEST_MOTOR "Motor"
|
||||
MSG_SELFTEST_NOTCONNECTED "Nezapojeno "
|
||||
MSG_SELFTEST_OK "Self test OK"
|
||||
MSG_SELFTEST_PLEASECHECK "Zkontrolujte :"
|
||||
MSG_SELFTEST_PRINT_FAN_SPEED "Tiskovy vent.:"
|
||||
MSG_SELFTEST_START "Self test start "
|
||||
MSG_SELFTEST_SWAPPED "Prohozene"
|
||||
MSG_SELFTEST_WIRINGERROR "Chyba zapojeni"
|
||||
MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
MSG_SET_HOME_OFFSETS "Nastav pocatek home"
|
||||
MSG_SET_ORIGIN "Nastav pocatek"
|
||||
MSG_SET_TEMPERATURE "Nastavte teplotu:"
|
||||
MSG_SETTINGS "Nastaveni"
|
||||
MSG_SEVERE_SKEW "Tezke zkoseni:"
|
||||
MSG_SHOW_END_STOPS "Stav konc. spin."
|
||||
MSG_SILENT_MODE_OFF "Mod [vys. vykon]"
|
||||
MSG_SILENT_MODE_ON "Mod [tichy]"
|
||||
MSG_SLIGHT_SKEW "Lehke zkoseni:"
|
||||
MSG_SORT_ALPHA "Trideni [Abeceda]"
|
||||
MSG_SORT_NONE "Trideni [Zadne]"
|
||||
MSG_SORT_TIME "Trideni [Cas]"
|
||||
MSG_SORTING "Trideni souboru"
|
||||
MSG_SPEED "Rychlost"
|
||||
MSG_STACK_ERROR "Chyba - Doslo k prepisu staticke pameti!"
|
||||
MSG_STATISTICS "Statistika "
|
||||
MSG_STATS_FILAMENTUSED "Filament : "
|
||||
MSG_STATS_PRINTTIME "Cas tisku : "
|
||||
MSG_STATS_TOTALFILAMENT "Filament celkem :"
|
||||
MSG_STATS_TOTALPRINTTIME "Celkovy cas :"
|
||||
MSG_STEALTH_MODE_OFF "Mod [Normal]"
|
||||
MSG_STEALTH_MODE_ON "Mod [Stealth]"
|
||||
MSG_STEEL_SHEET_CHECK "Je tiskovy plat na heatbed?"
|
||||
MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
MSG_STOP_PRINT "Zastavit tisk"
|
||||
MSG_STOPPED "STOPPED. "
|
||||
MSG_STORE_EPROM "Store memory"
|
||||
MSG_SUPPORT "Podpora"
|
||||
MSG_SWITCH_PS_OFF "Zapnout zdroj"
|
||||
MSG_SWITCH_PS_ON "Vypnout zdroj"
|
||||
MSG_TAKE_EFFECT " pro projeveni zmen"
|
||||
MSG_TEMP_CAL_FAILED "Teplotni kalibrace selhala"
|
||||
MSG_TEMP_CALIBRATION "Tepl. kal. "
|
||||
MSG_TEMP_CALIBRATION_DONE "Teplotni kalibrace dokoncena a je nyni aktivni. Teplotni kalibraci je mozno deaktivovat v menu Nastaveni->Tepl. kal."
|
||||
MSG_TEMP_CALIBRATION_OFF "Tepl. kal. [vyp]"
|
||||
MSG_TEMP_CALIBRATION_ON "Tepl. kal. [zap]"
|
||||
MSG_TEMPERATURE "Teplota"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
|
||||
MSG_TUNE "Ladit"
|
||||
MSG_UNLOAD_ALL "Vyjmout vse"
|
||||
MSG_UNLOAD_FILAMENT "Vyjmout filament"
|
||||
MSG_UNLOAD_FILAMENT_1 "Vyjmout filam. 1"
|
||||
MSG_UNLOAD_FILAMENT_2 "Vyjmout filam. 2"
|
||||
MSG_UNLOAD_FILAMENT_3 "Vyjmout filam. 3"
|
||||
MSG_UNLOAD_FILAMENT_4 "Vyjmout filam. 4"
|
||||
MSG_UNLOAD_SUCCESSFUL "Bylo vysunuti filamentu uspesne?"
|
||||
MSG_UNLOADING_FILAMENT "Vysouvam filament"
|
||||
MSG_USB_PRINTING "Tisk z USB "
|
||||
MSG_USED "Pouzite behem tisku"
|
||||
MSG_USERWAIT "Wait for user..."
|
||||
MSG_V2_CALIBRATION "Kal. prvni vrstvy"
|
||||
MSG_VOLUMETRIC "Filament"
|
||||
MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
MSG_WAITING_TEMP "Cekani na zchladnuti trysky a podlozky."
|
||||
MSG_WAITING_TEMP_PINDA "Cekani na zchladnuti PINDA"
|
||||
MSG_WATCH "Informace"
|
||||
MSG_WIZARD "Wizard"
|
||||
MSG_WIZARD_CALIBRATION_FAILED "Prosim nahlednete do manualu a opravte problem. Po te obnovte Wizarda rebootovanim tiskarny."
|
||||
MSG_WIZARD_CLEAN_HEATBED "Prosim ocistete heatbed a stisknete tlacitko."
|
||||
MSG_WIZARD_DONE "Vse je hotovo."
|
||||
MSG_WIZARD_FILAMENT_LOADED "Je filament zaveden?"
|
||||
MSG_WIZARD_HEATING "Predehrivam trysku. Prosim cekejte."
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT "Prosim zavedte PLA filament a po te obnovte Wizarda stisknutim reset tlacitka."
|
||||
MSG_WIZARD_LOAD_FILAMENT "Prosim vlozte PLA filament do extruderu, po te stisknete tlacitko pro zavedeni filamentu."
|
||||
MSG_WIZARD_PLA_FILAMENT "Je to PLA filament?"
|
||||
MSG_WIZARD_QUIT "Wizarda muzete kdykoliv znovu spustit z menu Calibration -> Wizard"
|
||||
MSG_WIZARD_REPEAT_V2_CAL "Chcete opakovat posledni krok a pozmenit vzdalenost mezi tryskou a heatbed?"
|
||||
MSG_WIZARD_RERUN "Spusteni Wizarda vymaze ulozene vysledky vsech kalibraci a spusti kalibracni proces od zacatku. Pokracovat?"
|
||||
MSG_WIZARD_SELFTEST "Nejdriv pomoci selftestu zkontoluji nejcastejsi chyby vznikajici pri sestaveni tiskarny."
|
||||
MSG_WIZARD_V2_CAL "Nyni zkalibruji vzdalenost mezi koncem trysky a povrchem heatbedu."
|
||||
MSG_WIZARD_V2_CAL_2 "Zacnu tisknout linku a Vy budete postupne snizovat trysku otacenim tlacitka dokud nedosahnete optimalni vysky. Prohlednete si obrazky v nasi prirucce v kapitole Kalibrace"
|
||||
MSG_WIZARD_WELCOME "Dobry den, jsem vase tiskarna Original Prusa i3. Chcete abych Vas provedla kalibracnim procesem?"
|
||||
MSG_WIZARD_WILL_PREHEAT "Nyni predehreji trysku pro PLA."
|
||||
MSG_WIZARD_XYZ_CAL "Nyni provedu xyz kalibraci. Zabere to priblizne 12 min."
|
||||
MSG_WIZARD_Z_CAL "Nyni provedu z kalibraci."
|
||||
MSG_XYZ_DETAILS "Detaily XYZ kal."
|
||||
MSG_Y_DISTANCE_FROM_MIN "Y vzdalenost od min:"
|
||||
MSG_YES "Ano"
|
||||
WELCOME_MSG CUSTOM_MENDEL_NAME " ok"
|
67
lang_upgrade/msgs_de.txt
Normal file
67
lang_upgrade/msgs_de.txt
Normal file
@ -0,0 +1,67 @@
|
||||
MSG_ALL "Alle"
|
||||
MSG_CALIBRATE_PINDA "Kalibrieren"
|
||||
MSG_CALIBRATION_PINDA_MENU "Temp. kalibrieren"
|
||||
MSG_CURRENT "Aktuelles"
|
||||
MSG_DATE "Datum"
|
||||
MSG_EXTRUDER "Extruder"
|
||||
MSG_EXTRUDER_1 "Extruder 1"
|
||||
MSG_EXTRUDER_2 "Extruder 2"
|
||||
MSG_EXTRUDER_3 "Extruder 3"
|
||||
MSG_EXTRUDER_4 "Extruder 4"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteration "
|
||||
MSG_FINISHING_MOVEMENTS "Bewegung beenden"
|
||||
MSG_CHOOSE_EXTRUDER "Waehlen Sie Extruder"
|
||||
MSG_LEFT "Links:"
|
||||
MSG_LOAD_ALL "Alle laden"
|
||||
MSG_LOAD_FILAMENT_1 "Filament 1 laden"
|
||||
MSG_LOAD_FILAMENT_2 "Filament 2 laden"
|
||||
MSG_LOAD_FILAMENT_3 "Filament 3 laden"
|
||||
MSG_LOAD_FILAMENT_4 "Filament 4 laden"
|
||||
MSG_M117_V2_CALIBRATION "M117 Erste-Schicht Kal."
|
||||
MSG_MEASURED_SKEW "Schraeglauf:"
|
||||
MSG_PID_EXTRUDER "PID Kalibrierung"
|
||||
MSG_PID_FINISHED "PID Kalib. fertig"
|
||||
MSG_PID_RUNNING "PID Kalib."
|
||||
MSG_PINDA_NOT_CALIBRATED "Temperatur wurde nicht kalibriert"
|
||||
MSG_PINDA_PREHEAT "PINDA erwaermen"
|
||||
MSG_PLA_FILAMENT_LOADED "Ist PLA Filament geladen?"
|
||||
MSG_PLEASE_LOAD_PLA "Bitte laden Sie zuerst PLA Filament."
|
||||
MSG_PREPARE_FILAMENT "Filam. bereithalten"
|
||||
MSG_PRINT_PAUSED "Druck pausiert"
|
||||
MSG_RESUMING_PRINT "Druck weitergehen"
|
||||
MSG_RIGHT "Rechts:"
|
||||
MSG_SET_TEMPERATURE "Temp. einsetzen"
|
||||
MSG_SEVERE_SKEW "Schwerer Schr.:"
|
||||
MSG_SLIGHT_SKEW "Leichter Schr.:"
|
||||
MSG_TEMP_CALIBRATION "Temp Kalib. "
|
||||
MSG_TEMP_CALIBRATION_DONE "Temp. Kalibrierung fertig. Klicken um weiter zu gehen."
|
||||
MSG_TEMP_CALIBRATION_OFF "Temp. Kal. [OFF]"
|
||||
MSG_TEMP_CALIBRATION_ON "Temp. Kal. [ON]"
|
||||
MSG_UNLOAD_ALL "Alles entladen"
|
||||
MSG_UNLOAD_FILAMENT_1 "Filam. 1 entladen"
|
||||
MSG_UNLOAD_FILAMENT_2 "Filam. 2 entladen"
|
||||
MSG_UNLOAD_FILAMENT_3 "Filam. 3 entladen"
|
||||
MSG_UNLOAD_FILAMENT_4 "Filam. 4 entladen"
|
||||
MSG_USED "Beim Druck benutzte"
|
||||
MSG_V2_CALIBRATION "Erste-Schicht Kal"
|
||||
MSG_WIZARD "Wizard"
|
||||
MSG_WIZARD_CALIBRATION_FAILED "Bitte ueberpruefen Sie unser Handbuch und beheben Sie das Problem. Fahren Sie dann mit dem Assistenten fort, indem Sie den Drucker neu starten."
|
||||
MSG_WIZARD_CLEAN_HEATBED "Bitte reinigen Sie das Heizbett und druecken Sie dann den Knopf."
|
||||
MSG_WIZARD_DONE "Alles wurde getan. Viel Spass beim Drucken!"
|
||||
MSG_WIZARD_FILAMENT_LOADED "Ist das Filament geladen?"
|
||||
MSG_WIZARD_HEATING "Vorheizen der Duese. Bitte warten."
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT "Bitte laden Sie PLA-Filament und fahren Sie mit dem Assistenten fort, indem Sie den Drucker neu starten."
|
||||
MSG_WIZARD_LOAD_FILAMENT "Fuehren Sie bitte PLA Filament in den Extruder und bestaetigen Sie den Knopf um es zu laden."
|
||||
MSG_WIZARD_PLA_FILAMENT "Ist es wirklich PLA Filament?"
|
||||
MSG_WIZARD_QUIT "Sie koennen immer den Asistenten im Menu neu aufrufen: Kalibrierung -> Assistant"
|
||||
MSG_WIZARD_REPEAT_V2_CAL "Moechten Sie den letzten Schritt wiederholen um den Abstand zwischen Duese und Druckbett neu einzustellen?"
|
||||
MSG_WIZARD_RERUN "Der laufende Assistent loescht die aktuelle Kalibrierergebnisse und wird von Anfang an beginnen. Fortsetzen?"
|
||||
MSG_WIZARD_SELFTEST "Zunaechst fuehre ich den Selbsttest durch um die haeufigsten Probleme bei der Aufbau zu ueberpruefen."
|
||||
MSG_WIZARD_V2_CAL "Jetzt werde ich den Abstand zwischen Duesenspitze und Druckbett kalibrieren."
|
||||
MSG_WIZARD_V2_CAL_2 "Ich werde jetzt erste Linie drucken. Waehrend des Druckes koennen Sie die Duese allmaehlich senken indem Sie den Knopf drehen, bis Sie die optimale Hoehe erreichen. Ueberpruefen Sie die Bilder in unserem Handbuch im Kapitel Kalibrierung"
|
||||
MSG_WIZARD_WELCOME "Hallo, ich bin dein Original Prusa i3 Drucker. Moechten Sie meine Hilfe durch den Setup-Prozess?"
|
||||
MSG_WIZARD_WILL_PREHEAT "Jetzt werde ich die Duese fuer PLA vorheizen. "
|
||||
MSG_WIZARD_XYZ_CAL "Ich werde jetzt die XYZ-Kalibrierung durchfuehren. Es wird ca. 12 Minuten dauern"
|
||||
MSG_WIZARD_Z_CAL "Ich werde jetzt die Z Kalibrierung durchfuehren."
|
||||
MSG_XYZ_DETAILS "XYZ Kal. Details"
|
||||
MSG_Y_DISTANCE_FROM_MIN "Y Entfernung vom min"
|
373
lang_upgrade/msgs_en.txt
Normal file
373
lang_upgrade/msgs_en.txt
Normal file
@ -0,0 +1,373 @@
|
||||
MSG_ADJUSTZ c=0 r=0 "Auto adjust Z?"
|
||||
MSG_ALL c=19 r=1 "All"
|
||||
MSG_AUTO_HOME c=0 r=0 "Auto home"
|
||||
MSG_AUTO_MODE_ON c=0 r=0 "Mode [auto power]"
|
||||
MSG_AUTOLOAD_FILAMENT c=17 r=0 "AutoLoad filament"
|
||||
MSG_AUTOLOADING_ENABLED c=20 r=4 "Autoloading filament is active, just press the knob and insert filament..."
|
||||
MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4 "Autoloading filament available only when filament sensor is turned on..."
|
||||
MSG_BABYSTEP_X c=0 r=0 "Babystep X"
|
||||
MSG_BABYSTEP_Y c=0 r=0 "Babystep Y"
|
||||
MSG_BABYSTEP_Z c=0 r=0 "Live adjust Z"
|
||||
MSG_BABYSTEP_Z_NOT_SET c=20 r=12 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
|
||||
MSG_BABYSTEPPING_X c=0 r=0 "Babystepping X"
|
||||
MSG_BABYSTEPPING_Y c=0 r=0 "Babystepping Y"
|
||||
MSG_BABYSTEPPING_Z c=20 r=0 "Adjusting Z"
|
||||
MSG_BED c=0 r=0 "Bed"
|
||||
MSG_BED_CORRECTION_FRONT c=14 r=1 "Front side[um]"
|
||||
MSG_BED_CORRECTION_LEFT c=14 r=1 "Left side [um]"
|
||||
MSG_BED_CORRECTION_MENU c=0 r=0 "Bed level correct"
|
||||
MSG_BED_CORRECTION_REAR c=14 r=1 "Rear side [um]"
|
||||
MSG_BED_CORRECTION_RESET c=0 r=0 "Reset"
|
||||
MSG_BED_CORRECTION_RIGHT c=14 r=1 "Right side[um]"
|
||||
MSG_BED_DONE c=0 r=0 "Bed done"
|
||||
MSG_BED_HEATING c=0 r=0 "Bed Heating"
|
||||
MSG_BED_HEATING_SAFETY_DISABLED c=0 r=0 "Heating disabled by safety timer."
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH c=20 r=4 "Bed leveling failed. Sensor triggered too high. Waiting for reset."
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED c=20 r=4 "Bed leveling failed. Sensor disconnected or cable broken. Waiting for reset."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR c=20 r=8 "XYZ calibration failed. Front calibration points not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR c=20 r=8 "XYZ calibration failed. Left front calibration point not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR c=20 r=8 "XYZ calibration failed. Right front calibration point not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED c=20 r=8 "XYZ calibration failed. Please consult the manual."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT c=20 r=8 "XYZ calibration ok. X/Y axes are perpendicular. Congratulations!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND c=20 r=8 "XYZ calibration failed. Bed calibration point was not found."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME c=20 r=8 "XYZ calibration all right. Skew will be corrected automatically."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD c=20 r=8 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR c=20 r=8 "XYZ calibration compromised. Front calibration points not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR c=20 r=8 "XYZ calibration compromised. Left front calibration point not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR c=20 r=8 "XYZ calibration compromised. Right front calibration point not reachable."
|
||||
MSG_BEGIN_FILE_LIST c=0 r=0 "Begin file list"
|
||||
MSG_CALIBRATE_BED c=0 r=0 "Calibrate XYZ"
|
||||
MSG_CALIBRATE_BED_RESET c=0 r=0 "Reset XYZ calibr."
|
||||
MSG_CALIBRATE_E c=20 r=1 "Calibrate E"
|
||||
MSG_CALIBRATE_PINDA c=17 r=1 "Calibrate"
|
||||
MSG_CALIBRATE_Z_AUTO c=20 r=2 "Calibrating Z"
|
||||
MSG_CALIBRATION_PINDA_MENU c=17 r=1 "Temp. calibration"
|
||||
MSG_CARD_MENU c=0 r=0 "Print from SD"
|
||||
MSG_CLEAN_NOZZLE_E c=20 r=8 "E calibration finished. Please clean the nozzle. Click when done."
|
||||
MSG_CNG_SDCARD c=0 r=0 "Change SD card"
|
||||
MSG_CONFIGURATION_VER c=0 r=0 " Last Updated: "
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP c=20 r=2 "Are left and right Z~carriages all up?"
|
||||
MSG_CONFIRM_NOZZLE_CLEAN c=20 r=8 "Please clean the nozzle for calibration. Click when done."
|
||||
MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ c=20 r=8 "Filaments are now adjusted. Please clean the nozzle for calibration. Click when done."
|
||||
MSG_CONTROL c=0 r=0 "Control"
|
||||
MSG_COOLDOWN c=0 r=0 "Cooldown"
|
||||
MSG_CORRECTLY c=20 r=0 "Changed correctly?"
|
||||
MSG_CRASH_DET_ONLY_IN_NORMAL c=20 r=4 "\x1b[2JCrash detection can\x1b[1;0Hbe turned on only in\x1b[2;0HNormal mode"
|
||||
MSG_CRASH_DET_STEALTH_FORCE_OFF c=20 r=4 "\x1b[2JWARNING:\x1b[1;0HCrash detection\x1b[2;0Hdisabled in\x1b[3;0HStealth mode"
|
||||
MSG_CRASH_DETECTED c=20 r=1 "Crash detected."
|
||||
MSG_CRASH_DETECTED2 c=20 r=2 "Crash detected. Continue printing?"
|
||||
MSG_CRASHDETECT_NA c=0 r=0 "Crash det. [N/A]"
|
||||
MSG_CRASHDETECT_OFF c=0 r=0 "Crash det. [off]"
|
||||
MSG_CRASHDETECT_ON c=0 r=0 "Crash det. [on]"
|
||||
MSG_CURRENT c=19 r=1 "Current"
|
||||
MSG_DATE c=17 r=1 "Date:"
|
||||
MSG_DEFAULT_SETTINGS_LOADED c=20 r=4 "Old settings found. Default PID, Esteps etc. will be set."
|
||||
MSG_DISABLE_STEPPERS c=0 r=0 "Disable steppers"
|
||||
MSG_DWELL c=0 r=0 "Sleep..."
|
||||
MSG_E_CAL_KNOB c=20 r=8 "Rotate knob until mark reaches extruder body. Click when done."
|
||||
MSG_END_FILE_LIST c=0 r=0 "End file list"
|
||||
MSG_ENDSTOP_HIT c=0 r=0 "TRIGGERED"
|
||||
MSG_ENDSTOP_OPEN c=0 r=0 "open"
|
||||
MSG_ENDSTOPS_HIT c=0 r=0 "endstops hit: "
|
||||
MSG_Enqueing c=0 r=0 "enqueing \""
|
||||
MSG_ERR_COLD_EXTRUDE_STOP c=0 r=0 " cold extrusion prevented"
|
||||
MSG_ERR_CHECKSUM_MISMATCH c=0 r=0 "checksum mismatch, Last Line: "
|
||||
MSG_ERR_KILLED c=0 r=0 "Printer halted. kill() called!"
|
||||
MSG_ERR_NO_CHECKSUM c=0 r=0 "No Checksum with line number, Last Line: "
|
||||
MSG_ERR_NO_THERMISTORS c=0 r=0 "No thermistors - no temperature"
|
||||
MSG_ERR_STOPPED c=0 r=0 "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
MSG_ERROR c=0 r=0 "ERROR:"
|
||||
MSG_EXTRUDER c=17 r=1 "Extruder"
|
||||
MSG_EXTRUDER_1 c=17 r=1 "Extruder 1"
|
||||
MSG_EXTRUDER_2 c=17 r=1 "Extruder 2"
|
||||
MSG_EXTRUDER_3 c=17 r=1 "Extruder 3"
|
||||
MSG_EXTRUDER_4 c=17 r=1 "Extruder 4"
|
||||
MSG_EXTRUDER_CORRECTION c=9 r=0 "E-correct"
|
||||
MSG_EXTRUDER_CORRECTION_OFF c=6 r=0 " [off"
|
||||
MSG_FACTOR c=0 r=0 " \002 Fact"
|
||||
MSG_FAN_SPEED c=14 r=0 "Fan speed"
|
||||
MSG_FANS_CHECK_OFF c=17 r=1 "Fans check [off]"
|
||||
MSG_FANS_CHECK_ON c=17 r=1 "Fans check [on]"
|
||||
MSG_FIL_ADJUSTING c=20 r=4 "Adjusting filaments. Please wait."
|
||||
MSG_FILAMENT_CLEAN c=20 r=2 "Filament extruding & with correct color?"
|
||||
MSG_FILAMENT_LOADING_T0 c=20 r=4 "Insert filament into extruder 1. Click when done."
|
||||
MSG_FILAMENT_LOADING_T1 c=20 r=4 "Insert filament into extruder 2. Click when done."
|
||||
MSG_FILAMENT_LOADING_T2 c=20 r=4 "Insert filament into extruder 3. Click when done."
|
||||
MSG_FILAMENT_LOADING_T3 c=20 r=4 "Insert filament into extruder 4. Click when done."
|
||||
MSG_FILAMENT_SENSOR c=20 r=0 "Filament sensor"
|
||||
MSG_FILAMENTCHANGE c=0 r=0 "Change filament"
|
||||
MSG_FILE_CNT c=20 r=4 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
|
||||
MSG_FILE_INCOMPLETE c=20 r=2 "File incomplete. Continue anyway?"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION c=20 r=0 "Iteration "
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 c=60 r=0 "Searching bed calibration point"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 c=14 r=0 " of 4"
|
||||
MSG_FINISHING_MOVEMENTS c=20 r=1 "Finishing movements"
|
||||
MSG_FLOW c=0 r=0 "Flow"
|
||||
MSG_FLOW0 c=0 r=0 "Flow 0"
|
||||
MSG_FLOW1 c=0 r=0 "Flow 1"
|
||||
MSG_FLOW2 c=0 r=0 "Flow 2"
|
||||
MSG_FOLLOW_CALIBRATION_FLOW c=20 r=8 "Printer has not been calibrated yet. Please follow the manual, chapter First steps, section Calibration flow."
|
||||
MSG_FORCE_SELFTEST c=20 r=8 "Selftest will be run to calibrate accurate sensorless rehoming."
|
||||
MSG_FREE_MEMORY c=0 r=0 " Free Memory: "
|
||||
MSG_FSENS_AUTOLOAD_NA c=17 r=1 "F. autoload [N/A]"
|
||||
MSG_FSENS_AUTOLOAD_OFF c=17 r=1 "F. autoload [off]"
|
||||
MSG_FSENS_AUTOLOAD_ON c=17 r=1 "F. autoload [on]"
|
||||
MSG_FSENS_NOT_RESPONDING c=20 r=4 "ERROR: Filament sensor is not responding, please check connection."
|
||||
MSG_FSENSOR_NA c=0 r=0 "Fil. sensor [N/A]"
|
||||
MSG_FSENSOR_OFF c=0 r=0 "Fil. sensor [off]"
|
||||
MSG_FSENSOR_ON c=0 r=0 "Fil. sensor [on]"
|
||||
MSG_FW_VERSION_ALPHA c=20 r=8 "You are using firmware alpha version. This is development version. Using this version is not recommended and may cause printer damage."
|
||||
MSG_FW_VERSION_BETA c=20 r=8 "You are using firmware beta version. This is development version. Using this version is not recommended and may cause printer damage."
|
||||
MSG_FW_VERSION_RC c=20 r=8 "This firmware version is release candidate. Some of the features may not work properly."
|
||||
MSG_FW_VERSION_UNKNOWN c=20 r=8 "WARNING: This is an unofficial, unsupported build. Use at your own risk!"
|
||||
MSG_HEATING c=0 r=0 "Heating"
|
||||
MSG_HEATING_COMPLETE c=20 r=0 "Heating done."
|
||||
MSG_HOMEYZ c=0 r=0 "Calibrate Z"
|
||||
MSG_HOMEYZ_DONE c=0 r=0 "Calibration done"
|
||||
MSG_HOMEYZ_PROGRESS c=0 r=0 "Calibrating Z"
|
||||
MSG_CHANGE_EXTR c=20 r=1 "Change extruder"
|
||||
MSG_CHANGE_SUCCESS c=0 r=0 "Change success!"
|
||||
MSG_CHANGED_BOTH c=20 r=4 "Warning: both printer type and motherboard type changed."
|
||||
MSG_CHANGED_MOTHERBOARD c=20 r=4 "Warning: motherboard type changed."
|
||||
MSG_CHANGED_PRINTER c=20 r=4 "Warning: printer type changed."
|
||||
MSG_CHANGING_FILAMENT c=20 r=0 "Changing filament!"
|
||||
MSG_CHECK_IDLER c=20 r=4 "Please open idler and remove filament manually."
|
||||
MSG_CHOOSE_EXTRUDER c=20 r=1 "Choose extruder:"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 c=60 r=0 "Improving bed calibration point"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14 r=0 " of 4"
|
||||
MSG_INFO_EXTRUDER c=15 r=1 "Extruder info"
|
||||
MSG_INFO_FILAMENT_XDIFF c=11 r=1 "Fil. Xd:"
|
||||
MSG_INFO_FILAMENT_YDIFF c=11 r=1 "Fil. Ydiff:"
|
||||
MSG_INFO_NOZZLE_FAN c=11 r=1 "Nozzle FAN:"
|
||||
MSG_INFO_PRINT_FAN c=11 r=1 "Print FAN: "
|
||||
MSG_INIT_SDCARD c=0 r=0 "Init. SD card"
|
||||
MSG_INSERT_FILAMENT c=20 r=0 "Insert filament"
|
||||
MSG_KILLED c=0 r=0 "KILLED. "
|
||||
MSG_LANGUAGE_NAME c=0 r=0 "English"
|
||||
MSG_LANGUAGE_SELECT c=0 r=0 "Select language"
|
||||
MSG_LEFT c=12 r=1 "Left:"
|
||||
MSG_LOAD_ALL c=0 r=0 "Load all"
|
||||
MSG_LOAD_EPROM c=0 r=0 "Load memory"
|
||||
MSG_LOAD_FILAMENT c=17 r=0 "Load filament"
|
||||
MSG_LOAD_FILAMENT_1 c=17 r=0 "Load filament 1"
|
||||
MSG_LOAD_FILAMENT_2 c=17 r=0 "Load filament 2"
|
||||
MSG_LOAD_FILAMENT_3 c=17 r=0 "Load filament 3"
|
||||
MSG_LOAD_FILAMENT_4 c=17 r=0 "Load filament 4"
|
||||
MSG_LOADING_COLOR c=0 r=0 "Loading color"
|
||||
MSG_LOADING_FILAMENT c=20 r=0 "Loading filament"
|
||||
MSG_LOOSE_PULLEY c=20 r=1 "Loose pulley"
|
||||
MSG_M104_INVALID_EXTRUDER c=0 r=0 "M104 Invalid extruder "
|
||||
MSG_M105_INVALID_EXTRUDER c=0 r=0 "M105 Invalid extruder "
|
||||
MSG_M109_INVALID_EXTRUDER c=0 r=0 "M109 Invalid extruder "
|
||||
MSG_M117_V2_CALIBRATION c=25 r=1 "M117 First layer cal."
|
||||
MSG_M119_REPORT c=0 r=0 "Reporting endstop status"
|
||||
MSG_M200_INVALID_EXTRUDER c=0 r=0 "M200 Invalid extruder "
|
||||
MSG_M218_INVALID_EXTRUDER c=0 r=0 "M218 Invalid extruder "
|
||||
MSG_M221_INVALID_EXTRUDER c=0 r=0 "M221 Invalid extruder "
|
||||
MSG_MAIN c=0 r=0 "Main"
|
||||
MSG_MARK_FIL c=20 r=8 "Mark filament 100mm from extruder body. Click when done."
|
||||
MSG_MAX c=0 r=0 " \002 Max"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60 r=0 "Measuring reference height of calibration point"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 c=14 r=0 " of 9"
|
||||
MSG_MEASURED_OFFSET c=0 r=0 "[0;0] point offset"
|
||||
MSG_MEASURED_SKEW c=15 r=1 "Measured skew:"
|
||||
MSG_MENU_BELT_STATUS c=15 r=1 "Belt status"
|
||||
MSG_MENU_CALIBRATION c=0 r=0 "Calibration"
|
||||
MSG_MENU_TEMPERATURES c=15 r=1 "Temperatures"
|
||||
MSG_MENU_VOLTAGES c=15 r=1 "Voltages"
|
||||
MSG_MESH_BED_LEVELING c=0 r=0 "Mesh Bed Leveling"
|
||||
MSG_MIN c=0 r=0 " \002 Min"
|
||||
MSG_MOTION c=0 r=0 "Motion"
|
||||
MSG_MOVE_AXIS c=0 r=0 "Move axis"
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP c=20 r=8 "Calibrating XYZ. Rotate the knob to move the Z carriage up to the end stoppers. Click when done."
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z c=20 r=8 "Calibrating Z. Rotate the knob to move the Z carriage up to the end stoppers. Click when done."
|
||||
MSG_MOVE_E c=0 r=0 "Extruder"
|
||||
MSG_MOVE_X c=0 r=0 "Move X"
|
||||
MSG_MOVE_Y c=0 r=0 "Move Y"
|
||||
MSG_MOVE_Z c=0 r=0 "Move Z"
|
||||
MSG_NEW_FIRMWARE_AVAILABLE c=20 r=2 "New firmware version available:"
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE c=20 r=0 "Please upgrade."
|
||||
MSG_NO c=0 r=0 "No"
|
||||
MSG_NO_CARD c=0 r=0 "No SD card"
|
||||
MSG_NO_MOVE c=0 r=0 "No move."
|
||||
MSG_NOT_COLOR c=0 r=0 "Color not correct"
|
||||
MSG_NOT_LOADED c=19 r=0 "Filament not loaded"
|
||||
MSG_NOZZLE c=0 r=0 "Nozzle"
|
||||
MSG_NOZZLE1 c=0 r=0 "Nozzle2"
|
||||
MSG_NOZZLE2 c=0 r=0 "Nozzle3"
|
||||
MSG_OK c=0 r=0 "ok"
|
||||
MSG_PAPER c=20 r=8 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
|
||||
MSG_PAUSE_PRINT c=0 r=0 "Pause print"
|
||||
MSG_PICK_Z c=0 r=0 "Pick print"
|
||||
MSG_PID_EXTRUDER c=17 r=1 "PID calibration"
|
||||
MSG_PID_FINISHED c=20 r=1 "PID cal. finished"
|
||||
MSG_PID_RUNNING c=20 r=1 "PID cal. "
|
||||
MSG_PINDA_NOT_CALIBRATED c=20 r=4 "Temperature calibration has not been run yet"
|
||||
MSG_PINDA_PREHEAT c=20 r=1 "PINDA Heating"
|
||||
MSG_PLA_FILAMENT_LOADED c=20 r=2 "Is PLA filament loaded?"
|
||||
MSG_PLACE_STEEL_SHEET c=20 r=4 "Please place steel sheet on heatbed."
|
||||
MSG_PLANNER_BUFFER_BYTES c=0 r=0 " PlannerBufferBytes: "
|
||||
MSG_PLEASE_LOAD_PLA c=20 r=4 "Please load PLA filament first."
|
||||
MSG_PLEASE_WAIT c=20 r=0 "Please wait"
|
||||
MSG_POWERUP c=0 r=0 "PowerUp"
|
||||
MSG_PREHEAT c=0 r=0 "Preheat"
|
||||
MSG_PREHEAT_NOZZLE c=20 r=0 "Preheat the nozzle!"
|
||||
MSG_PREPARE_FILAMENT c=20 r=1 "Prepare new filament"
|
||||
MSG_PRESS c=20 r=0 "and press the knob"
|
||||
MSG_PRESS_TO_PREHEAT c=20 r=4 "Press knob to preheat nozzle and continue."
|
||||
MSG_PRESS_TO_UNLOAD c=20 r=4 "Please press the knob to unload filament"
|
||||
MSG_PRINT_ABORTED c=20 r=0 "Print aborted"
|
||||
MSG_PRINT_PAUSED c=20 r=1 "Print paused"
|
||||
MSG_PRINTER_DISCONNECTED c=20 r=1 "Printer disconnected"
|
||||
MSG_PRUSA3D c=0 r=0 "prusa3d.com"
|
||||
MSG_PRUSA3D_FORUM c=0 r=0 "forum.prusa3d.com"
|
||||
MSG_PRUSA3D_HOWTO c=0 r=0 "howto.prusa3d.com"
|
||||
MSG_PULL_OUT_FILAMENT c=20 r=4 "Please pull out filament immediately"
|
||||
MSG_REBOOT c=20 r=0 "Reboot the printer"
|
||||
MSG_RECOVER_PRINT c=20 r=2 "Blackout occurred. Recover print?"
|
||||
MSG_RECOVERING_PRINT c=20 r=1 "Recovering print "
|
||||
MSG_RECTRACT c=0 r=0 "Rectract"
|
||||
MSG_REFRESH c=0 r=0 "\xF8" "Refresh"
|
||||
MSG_REMOVE_STEEL_SHEET c=20 r=4 "Please remove steel sheet from heatbed."
|
||||
MSG_RESEND c=0 r=0 "Resend: "
|
||||
MSG_RESTORE_FAILSAFE c=0 r=0 "Restore failsafe"
|
||||
MSG_RESUME_PRINT c=0 r=0 "Resume print"
|
||||
MSG_RESUMING c=0 r=0 "Resuming print"
|
||||
MSG_RESUMING_PRINT c=20 r=1 "Resuming print"
|
||||
MSG_RIGHT c=12 r=1 "Right:"
|
||||
MSG_SD_CANT_ENTER_SUBDIR c=0 r=0 "Cannot enter subdir: "
|
||||
MSG_SD_CANT_OPEN_SUBDIR c=0 r=0 "Cannot open subdir"
|
||||
MSG_SD_CARD_OK c=0 r=0 "SD card ok"
|
||||
MSG_SD_ERR_WRITE_TO_FILE c=0 r=0 "error writing to file"
|
||||
MSG_SD_FILE_OPENED c=0 r=0 "File opened: "
|
||||
MSG_SD_FILE_SELECTED c=0 r=0 "File selected"
|
||||
MSG_SD_INIT_FAIL c=0 r=0 "SD init fail"
|
||||
MSG_SD_INSERTED c=0 r=0 "Card inserted"
|
||||
MSG_SD_NOT_PRINTING c=0 r=0 "Not SD printing"
|
||||
MSG_SD_OPEN_FILE_FAIL c=0 r=0 "open failed, File: "
|
||||
MSG_SD_OPENROOT_FAIL c=0 r=0 "openRoot failed"
|
||||
MSG_SD_PRINTING_BYTE c=0 r=0 "SD printing byte "
|
||||
MSG_SD_REMOVED c=0 r=0 "Card removed"
|
||||
MSG_SD_VOL_INIT_FAIL c=0 r=0 "volume.init failed"
|
||||
MSG_SD_WORKDIR_FAIL c=0 r=0 "workDir open failed"
|
||||
MSG_SD_WRITE_TO_FILE c=0 r=0 "Writing to file: "
|
||||
MSG_SECOND_SERIAL_OFF c=17 r=1 "RPi port [off]"
|
||||
MSG_SECOND_SERIAL_ON c=17 r=1 "RPi port [on]"
|
||||
MSG_SELFTEST c=0 r=0 "Selftest "
|
||||
MSG_SELFTEST_AXIS c=0 r=0 "Axis"
|
||||
MSG_SELFTEST_AXIS_LENGTH c=0 r=0 "Axis length"
|
||||
MSG_SELFTEST_BEDHEATER c=0 r=0 "Bed / Heater"
|
||||
MSG_SELFTEST_COOLING_FAN c=20 r=0 "Front print fan?"
|
||||
MSG_SELFTEST_ENDSTOP c=0 r=0 "Endstop"
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1 "Endstop not hit"
|
||||
MSG_SELFTEST_ENDSTOPS c=0 r=0 "Endstops"
|
||||
MSG_SELFTEST_ERROR c=0 r=0 "Selftest error !"
|
||||
MSG_SELFTEST_EXTRUDER_FAN c=20 r=0 "Left hotend fan?"
|
||||
MSG_SELFTEST_EXTRUDER_FAN_SPEED c=18 r=0 "Extruder fan:"
|
||||
MSG_SELFTEST_FAILED c=20 r=0 "Selftest failed "
|
||||
MSG_SELFTEST_FAN c=20 r=0 "Fan test"
|
||||
MSG_SELFTEST_FAN_NO c=19 r=0 "Not spinning"
|
||||
MSG_SELFTEST_FAN_YES c=19 r=0 "Spinning"
|
||||
MSG_SELFTEST_FANS c=0 r=0 "Front/left fans"
|
||||
MSG_SELFTEST_FILAMENT_SENSOR c=18 r=0 "Filament sensor:"
|
||||
MSG_SELFTEST_HEATERTHERMISTOR c=0 r=0 "Heater/Thermistor"
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT c=20 r=0 "All correct "
|
||||
MSG_SELFTEST_CHECK_BED c=20 r=0 "Checking bed "
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS c=20 r=0 "Checking endstops"
|
||||
MSG_SELFTEST_CHECK_FSENSOR c=20 r=0 "Checking sensors "
|
||||
MSG_SELFTEST_CHECK_HOTEND c=20 r=0 "Checking hotend "
|
||||
MSG_SELFTEST_CHECK_X c=20 r=0 "Checking X axis "
|
||||
MSG_SELFTEST_CHECK_Y c=20 r=0 "Checking Y axis "
|
||||
MSG_SELFTEST_CHECK_Z c=20 r=0 "Checking Z axis "
|
||||
MSG_SELFTEST_MOTOR c=0 r=0 "Motor"
|
||||
MSG_SELFTEST_NOTCONNECTED c=0 r=0 "Not connected"
|
||||
MSG_SELFTEST_OK c=0 r=0 "Self test OK"
|
||||
MSG_SELFTEST_PLEASECHECK c=0 r=0 "Please check :"
|
||||
MSG_SELFTEST_PRINT_FAN_SPEED c=18 r=0 "Print fan:"
|
||||
MSG_SELFTEST_START c=20 r=0 "Self test start "
|
||||
MSG_SELFTEST_SWAPPED c=0 r=0 "Swapped"
|
||||
MSG_SELFTEST_WIRINGERROR c=0 r=0 "Wiring error"
|
||||
MSG_SERIAL_ERROR_MENU_STRUCTURE c=0 r=0 "Error in menu structure"
|
||||
MSG_SET_HOME_OFFSETS c=0 r=0 "Set home offsets"
|
||||
MSG_SET_ORIGIN c=0 r=0 "Set origin"
|
||||
MSG_SET_TEMPERATURE c=19 r=1 "Set temperature:"
|
||||
MSG_SETTINGS c=0 r=0 "Settings"
|
||||
MSG_SEVERE_SKEW c=15 r=1 "Severe skew:"
|
||||
MSG_SHOW_END_STOPS c=17 r=1 "Show end stops"
|
||||
MSG_SILENT_MODE_OFF c=0 r=0 "Mode [high power]"
|
||||
MSG_SILENT_MODE_ON c=0 r=0 "Mode [silent]"
|
||||
MSG_SLIGHT_SKEW c=15 r=1 "Slight skew:"
|
||||
MSG_SORT_ALPHA c=17 r=1 "Sort: [Alphabet]"
|
||||
MSG_SORT_NONE c=17 r=1 "Sort: [None]"
|
||||
MSG_SORT_TIME c=17 r=1 "Sort: [Time]"
|
||||
MSG_SORTING c=20 r=1 "Sorting files"
|
||||
MSG_SPEED c=0 r=0 "Speed"
|
||||
MSG_STACK_ERROR c=20 r=4 "Error - static memory has been overwritten"
|
||||
MSG_STATISTICS c=0 r=0 "Statistics "
|
||||
MSG_STATS_FILAMENTUSED c=20 r=0 "Filament used: "
|
||||
MSG_STATS_PRINTTIME c=20 r=0 "Print time: "
|
||||
MSG_STATS_TOTALFILAMENT c=20 r=0 "Total filament :"
|
||||
MSG_STATS_TOTALPRINTTIME c=20 r=0 "Total print time :"
|
||||
MSG_STEALTH_MODE_OFF c=0 r=0 "Mode [Normal]"
|
||||
MSG_STEALTH_MODE_ON c=0 r=0 "Mode [Stealth]"
|
||||
MSG_STEEL_SHEET_CHECK c=20 r=2 "Is steel sheet on heatbed?"
|
||||
MSG_STEPPER_TIMER_OVERFLOW_ERROR c=20 r=4 "Error - stepper timer overflow"
|
||||
MSG_STEPPER_TOO_HIGH c=0 r=0 "Steprate too high: "
|
||||
MSG_STOP_PRINT c=0 r=0 "Stop print"
|
||||
MSG_STOPPED c=0 r=0 "STOPPED. "
|
||||
MSG_STORE_EPROM c=0 r=0 "Store memory"
|
||||
MSG_SUPPORT c=0 r=0 "Support"
|
||||
MSG_SWITCH_PS_OFF c=0 r=0 "Switch power off"
|
||||
MSG_SWITCH_PS_ON c=0 r=0 "Switch power on"
|
||||
MSG_TAKE_EFFECT c=20 r=0 " for take effect"
|
||||
MSG_TEMP_CAL_FAILED c=20 r=8 "Temperature calibration failed"
|
||||
MSG_TEMP_CAL_WARNING c=20 r=4 "Stable ambient temperature 21-26C is needed a rigid stand is required."
|
||||
MSG_TEMP_CALIBRATION c=20 r=1 "Temp. cal. "
|
||||
MSG_TEMP_CALIBRATION_DONE c=20 r=12 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
|
||||
MSG_TEMP_CALIBRATION_OFF c=20 r=1 "Temp. cal. [off]"
|
||||
MSG_TEMP_CALIBRATION_ON c=20 r=1 "Temp. cal. [on]"
|
||||
MSG_TEMPERATURE c=0 r=0 "Temperature"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1 "SD card [normal]"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1 "SD card [FlshAir]"
|
||||
MSG_TUNE c=0 r=0 "Tune"
|
||||
MSG_UNLOAD_ALL c=0 r=0 "Unload all"
|
||||
MSG_UNLOAD_FILAMENT c=17 r=0 "Unload filament"
|
||||
MSG_UNLOAD_FILAMENT_1 c=17 r=0 "Unload filament 1"
|
||||
MSG_UNLOAD_FILAMENT_2 c=17 r=0 "Unload filament 2"
|
||||
MSG_UNLOAD_FILAMENT_3 c=17 r=0 "Unload filament 3"
|
||||
MSG_UNLOAD_FILAMENT_4 c=17 r=0 "Unload filament 4"
|
||||
MSG_UNLOAD_SUCCESSFUL c=20 r=2 "Was filament unload successful?"
|
||||
MSG_UNLOADING_FILAMENT c=20 r=1 "Unloading filament"
|
||||
MSG_USB_PRINTING c=0 r=0 "USB printing "
|
||||
MSG_USED c=19 r=1 "Used during print"
|
||||
MSG_USERWAIT c=0 r=0 "Wait for user..."
|
||||
MSG_V2_CALIBRATION c=17 r=1 "First layer cal."
|
||||
MSG_VOLUMETRIC c=0 r=0 "Filament"
|
||||
MSG_VOLUMETRIC_ENABLED c=0 r=0 "E in mm3"
|
||||
MSG_WAITING_TEMP c=20 r=3 "Waiting for nozzle and bed cooling"
|
||||
MSG_WAITING_TEMP_PINDA c=20 r=3 "Waiting for PINDA probe cooling"
|
||||
MSG_WATCH c=0 r=0 "Info screen"
|
||||
MSG_WIZARD c=17 r=1 "Wizard"
|
||||
MSG_WIZARD_CALIBRATION_FAILED c=20 r=8 "Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
MSG_WIZARD_CLEAN_HEATBED c=20 r=8 "Please clean heatbed and then press the knob."
|
||||
MSG_WIZARD_DONE c=20 r=8 "All is done. Happy printing!"
|
||||
MSG_WIZARD_FILAMENT_LOADED c=20 r=2 "Is filament loaded?"
|
||||
MSG_WIZARD_HEATING c=20 r=3 "Preheating nozzle. Please wait."
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT c=20 r=8 "Please load PLA filament and then resume Wizard by rebooting the printer."
|
||||
MSG_WIZARD_LOAD_FILAMENT c=20 r=8 "Please insert PLA filament to the extruder, then press knob to load it."
|
||||
MSG_WIZARD_PLA_FILAMENT c=20 r=2 "Is it PLA filament?"
|
||||
MSG_WIZARD_QUIT c=20 r=8 "You can always resume the Wizard from Calibration -> Wizard."
|
||||
MSG_WIZARD_REPEAT_V2_CAL c=20 r=7 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
|
||||
MSG_WIZARD_RERUN c=20 r=7 "Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
MSG_WIZARD_SELFTEST c=20 r=8 "First, I will run the selftest to check most common assembly problems."
|
||||
MSG_WIZARD_V2_CAL c=20 r=8 "Now I will calibrate distance between tip of the nozzle and heatbed surface."
|
||||
MSG_WIZARD_V2_CAL_2 c=20 r=12 "I will start to print line and you will gradually lower the nozzle by rotating the knob, until you reach optimal height. Check the pictures in our handbook in chapter Calibration."
|
||||
MSG_WIZARD_WELCOME c=20 r=7 "Hi, I am your Original Prusa i3 printer. Would you like me to guide you through the setup process?"
|
||||
MSG_WIZARD_WILL_PREHEAT c=20 r=4 "Now I will preheat nozzle for PLA."
|
||||
MSG_WIZARD_XYZ_CAL c=20 r=8 "I will run xyz calibration now. It will take approx. 12 mins."
|
||||
MSG_WIZARD_Z_CAL c=20 r=8 "I will run z calibration now."
|
||||
MSG_XYZ_DETAILS c=19 r=1 "XYZ cal. details"
|
||||
MSG_Y_DISTANCE_FROM_MIN c=20 r=1 "Y distance from min:"
|
||||
MSG_YES c=0 r=0 "Yes"
|
||||
WELCOME_MSG c=20 r=0 CUSTOM_MENDEL_NAME " ready."
|
30
lang_upgrade/msgs_en_unused.txt
Normal file
30
lang_upgrade/msgs_en_unused.txt
Normal file
@ -0,0 +1,30 @@
|
||||
MSG_BABYSTEP_X c=0 r=0 "Babystep X"
|
||||
MSG_BABYSTEP_Y c=0 r=0 "Babystep Y"
|
||||
MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ c=20 r=8 "Filaments are now adjusted. Please clean the nozzle for calibration. Click when done."
|
||||
MSG_CONTROL c=0 r=0 "Control"
|
||||
MSG_CRASH_DETECTED2 c=20 r=2 "Crash detected. Continue printing?"
|
||||
MSG_FIL_ADJUSTING c=20 r=4 "Adjusting filaments. Please wait."
|
||||
MSG_FLOW0 c=0 r=0 "Flow 0"
|
||||
MSG_FLOW1 c=0 r=0 "Flow 1"
|
||||
MSG_FLOW2 c=0 r=0 "Flow 2"
|
||||
MSG_FW_VERSION_RC c=20 r=8 "This firmware version is release candidate. Some of the features may not work properly."
|
||||
MSG_INFO_FILAMENT_XDIFF c=11 r=1 "Fil. Xd:"
|
||||
MSG_INFO_FILAMENT_YDIFF c=11 r=1 "Fil. Ydiff:"
|
||||
MSG_LANGUAGE_NAME c=0 r=0 "English"
|
||||
MSG_LOAD_EPROM c=0 r=0 "Load memory"
|
||||
MSG_MOTION c=0 r=0 "Motion"
|
||||
MSG_REBOOT c=20 r=0 "Reboot the printer"
|
||||
MSG_RECTRACT c=0 r=0 "Rectract"
|
||||
MSG_RESTORE_FAILSAFE c=0 r=0 "Restore failsafe"
|
||||
MSG_SD_NOT_PRINTING c=0 r=0 "Not SD printing"
|
||||
MSG_SERIAL_ERROR_MENU_STRUCTURE c=0 r=0 "Error in menu structure"
|
||||
MSG_SET_HOME_OFFSETS c=0 r=0 "Set home offsets"
|
||||
MSG_SET_ORIGIN c=0 r=0 "Set origin"
|
||||
MSG_STEPPER_TIMER_OVERFLOW_ERROR c=20 r=4 "Error - stepper timer overflow"
|
||||
MSG_STORE_EPROM c=0 r=0 "Store memory"
|
||||
MSG_SWITCH_PS_OFF c=0 r=0 "Switch power off"
|
||||
MSG_SWITCH_PS_ON c=0 r=0 "Switch power on"
|
||||
MSG_TAKE_EFFECT c=20 r=0 " for take effect"
|
||||
MSG_USB_PRINTING c=0 r=0 "USB printing "
|
||||
MSG_VOLUMETRIC c=0 r=0 "Filament"
|
||||
MSG_VOLUMETRIC_ENABLED c=0 r=0 "E in mm3"
|
96
lang_upgrade/msgs_en_used_more.txt
Normal file
96
lang_upgrade/msgs_en_used_more.txt
Normal file
@ -0,0 +1,96 @@
|
||||
MSG_ALL c=19 r=1 "All"
|
||||
MSG_AUTO_HOME c=0 r=0 "Auto home"
|
||||
MSG_AUTO_MODE_ON c=0 r=0 "Mode [auto power]"
|
||||
MSG_BABYSTEP_Z c=0 r=0 "Live adjust Z"
|
||||
MSG_BABYSTEP_Z_NOT_SET c=20 r=12 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
|
||||
MSG_BED c=0 r=0 "Bed"
|
||||
MSG_BED_DONE c=0 r=0 "Bed done"
|
||||
MSG_BED_HEATING c=0 r=0 "Bed Heating"
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED c=20 r=8 "XYZ calibration failed. Please consult the manual."
|
||||
MSG_CALIBRATE_Z_AUTO c=20 r=2 "Calibrating Z"
|
||||
MSG_CARD_MENU c=0 r=0 "Print from SD"
|
||||
MSG_CONFIRM_NOZZLE_CLEAN c=20 r=8 "Please clean the nozzle for calibration. Click when done."
|
||||
MSG_COOLDOWN c=0 r=0 "Cooldown"
|
||||
MSG_CRASH_DETECTED c=20 r=1 "Crash detected."
|
||||
MSG_CRASHDETECT_NA c=0 r=0 "Crash det. [N/A]"
|
||||
MSG_CRASHDETECT_OFF c=0 r=0 "Crash det. [off]"
|
||||
MSG_CRASHDETECT_ON c=0 r=0 "Crash det. [on]"
|
||||
MSG_ENDSTOP_HIT c=0 r=0 "TRIGGERED"
|
||||
MSG_ENDSTOP_OPEN c=0 r=0 "open"
|
||||
MSG_ENDSTOPS_HIT c=0 r=0 "endstops hit: "
|
||||
MSG_Enqueing c=0 r=0 "enqueing \""
|
||||
MSG_ERR_STOPPED c=0 r=0 "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
MSG_ERROR c=0 r=0 "ERROR:"
|
||||
MSG_EXTRUDER c=17 r=1 "Extruder"
|
||||
MSG_FAN_SPEED c=14 r=0 "Fan speed"
|
||||
MSG_FILAMENT_CLEAN c=20 r=2 "Filament extruding & with correct color?"
|
||||
MSG_FILAMENT_LOADING_T0 c=20 r=4 "Insert filament into extruder 1. Click when done."
|
||||
MSG_FILAMENT_LOADING_T1 c=20 r=4 "Insert filament into extruder 2. Click when done."
|
||||
MSG_FILAMENT_LOADING_T2 c=20 r=4 "Insert filament into extruder 3. Click when done."
|
||||
MSG_FILAMENT_LOADING_T3 c=20 r=4 "Insert filament into extruder 4. Click when done."
|
||||
MSG_FILAMENTCHANGE c=0 r=0 "Change filament"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 c=60 r=0 "Searching bed calibration point"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 c=14 r=0 " of 4"
|
||||
MSG_FINISHING_MOVEMENTS c=20 r=1 "Finishing movements"
|
||||
MSG_FOLLOW_CALIBRATION_FLOW c=20 r=8 "Printer has not been calibrated yet. Please follow the manual, chapter First steps, section Calibration flow."
|
||||
MSG_FSENS_AUTOLOAD_NA c=17 r=1 "F. autoload [N/A]"
|
||||
MSG_FSENSOR_OFF c=0 r=0 "Fil. sensor [off]"
|
||||
MSG_FSENSOR_ON c=0 r=0 "Fil. sensor [on]"
|
||||
MSG_HEATING c=0 r=0 "Heating"
|
||||
MSG_HEATING_COMPLETE c=20 r=0 "Heating done."
|
||||
MSG_HOMEYZ c=0 r=0 "Calibrate Z"
|
||||
MSG_CHOOSE_EXTRUDER c=20 r=1 "Choose extruder:"
|
||||
MSG_LOAD_FILAMENT c=17 r=0 "Load filament"
|
||||
MSG_LOADING_FILAMENT c=20 r=0 "Loading filament"
|
||||
MSG_M117_V2_CALIBRATION c=25 r=1 "M117 First layer cal."
|
||||
MSG_MAIN c=0 r=0 "Main"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60 r=0 "Measuring reference height of calibration point"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 c=14 r=0 " of 9"
|
||||
MSG_MENU_CALIBRATION c=0 r=0 "Calibration"
|
||||
MSG_NO c=0 r=0 "No"
|
||||
MSG_NOZZLE c=0 r=0 "Nozzle"
|
||||
MSG_OK c=0 r=0 "ok"
|
||||
MSG_PAPER c=20 r=8 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
|
||||
MSG_PLACE_STEEL_SHEET c=20 r=4 "Please place steel sheet on heatbed."
|
||||
MSG_PLEASE_WAIT c=20 r=0 "Please wait"
|
||||
MSG_POWERUP c=0 r=0 "PowerUp"
|
||||
MSG_PREHEAT_NOZZLE c=20 r=0 "Preheat the nozzle!"
|
||||
MSG_PRESS_TO_UNLOAD c=20 r=4 "Please press the knob to unload filament"
|
||||
MSG_PRINT_ABORTED c=20 r=0 "Print aborted"
|
||||
MSG_PULL_OUT_FILAMENT c=20 r=4 "Please pull out filament immediately"
|
||||
MSG_RECOVER_PRINT c=20 r=2 "Blackout occurred. Recover print?"
|
||||
MSG_REFRESH c=0 r=0 "\xF8" "Refresh"
|
||||
MSG_REMOVE_STEEL_SHEET c=20 r=4 "Please remove steel sheet from heatbed."
|
||||
MSG_SD_ERR_WRITE_TO_FILE c=0 r=0 "error writing to file"
|
||||
MSG_SD_OPEN_FILE_FAIL c=0 r=0 "open failed, File: "
|
||||
MSG_SD_WORKDIR_FAIL c=0 r=0 "workDir open failed"
|
||||
MSG_SELFTEST_COOLING_FAN c=20 r=0 "Front print fan?"
|
||||
MSG_SELFTEST_EXTRUDER_FAN c=20 r=0 "Left hotend fan?"
|
||||
MSG_SELFTEST_FAILED c=20 r=0 "Selftest failed "
|
||||
MSG_SELFTEST_FAN c=20 r=0 "Fan test"
|
||||
MSG_SELFTEST_FAN_NO c=19 r=0 "Not spinning"
|
||||
MSG_SELFTEST_FAN_YES c=19 r=0 "Spinning"
|
||||
MSG_SELFTEST_CHECK_BED c=20 r=0 "Checking bed "
|
||||
MSG_SELFTEST_CHECK_FSENSOR c=20 r=0 "Checking sensors "
|
||||
MSG_SELFTEST_MOTOR c=0 r=0 "Motor"
|
||||
MSG_SELFTEST_WIRINGERROR c=0 r=0 "Wiring error"
|
||||
MSG_SETTINGS c=0 r=0 "Settings"
|
||||
MSG_SILENT_MODE_OFF c=0 r=0 "Mode [high power]"
|
||||
MSG_SILENT_MODE_ON c=0 r=0 "Mode [silent]"
|
||||
MSG_STEALTH_MODE_OFF c=0 r=0 "Mode [Normal]"
|
||||
MSG_STEALTH_MODE_ON c=0 r=0 "Mode [Stealth]"
|
||||
MSG_STEEL_SHEET_CHECK c=20 r=2 "Is steel sheet on heatbed?"
|
||||
MSG_STOP_PRINT c=0 r=0 "Stop print"
|
||||
MSG_STOPPED c=0 r=0 "STOPPED. "
|
||||
MSG_TEMP_CALIBRATION c=20 r=1 "Temp. cal. "
|
||||
MSG_TEMP_CALIBRATION_DONE c=20 r=12 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
|
||||
MSG_UNLOAD_FILAMENT c=17 r=0 "Unload filament"
|
||||
MSG_UNLOADING_FILAMENT c=20 r=1 "Unloading filament"
|
||||
MSG_WATCH c=0 r=0 "Info screen"
|
||||
MSG_WIZARD_CALIBRATION_FAILED c=20 r=8 "Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
MSG_WIZARD_DONE c=20 r=8 "All is done. Happy printing!"
|
||||
MSG_WIZARD_HEATING c=20 r=3 "Preheating nozzle. Please wait."
|
||||
MSG_WIZARD_QUIT c=20 r=8 "You can always resume the Wizard from Calibration -> Wizard."
|
||||
MSG_YES c=0 r=0 "Yes"
|
||||
WELCOME_MSG c=20 r=0 CUSTOM_MENDEL_NAME " ready."
|
247
lang_upgrade/msgs_en_used_once.txt
Normal file
247
lang_upgrade/msgs_en_used_once.txt
Normal file
@ -0,0 +1,247 @@
|
||||
MSG_ADJUSTZ c=0 r=0 "Auto adjust Z?"
|
||||
MSG_AUTOLOAD_FILAMENT c=17 r=0 "AutoLoad filament"
|
||||
MSG_AUTOLOADING_ENABLED c=20 r=4 "Autoloading filament is active, just press the knob and insert filament..."
|
||||
MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4 "Autoloading filament available only when filament sensor is turned on..."
|
||||
MSG_BABYSTEPPING_X c=0 r=0 "Babystepping X"
|
||||
MSG_BABYSTEPPING_Y c=0 r=0 "Babystepping Y"
|
||||
MSG_BABYSTEPPING_Z c=20 r=0 "Adjusting Z"
|
||||
MSG_BED_CORRECTION_FRONT c=14 r=1 "Front side[um]"
|
||||
MSG_BED_CORRECTION_LEFT c=14 r=1 "Left side [um]"
|
||||
MSG_BED_CORRECTION_MENU c=0 r=0 "Bed level correct"
|
||||
MSG_BED_CORRECTION_REAR c=14 r=1 "Rear side [um]"
|
||||
MSG_BED_CORRECTION_RESET c=0 r=0 "Reset"
|
||||
MSG_BED_CORRECTION_RIGHT c=14 r=1 "Right side[um]"
|
||||
MSG_BED_HEATING_SAFETY_DISABLED c=0 r=0 "Heating disabled by safety timer."
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH c=20 r=4 "Bed leveling failed. Sensor triggered too high. Waiting for reset."
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED c=20 r=4 "Bed leveling failed. Sensor disconnected or cable broken. Waiting for reset."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR c=20 r=8 "XYZ calibration failed. Front calibration points not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR c=20 r=8 "XYZ calibration failed. Left front calibration point not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR c=20 r=8 "XYZ calibration failed. Right front calibration point not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT c=20 r=8 "XYZ calibration ok. X/Y axes are perpendicular. Congratulations!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND c=20 r=8 "XYZ calibration failed. Bed calibration point was not found."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME c=20 r=8 "XYZ calibration all right. Skew will be corrected automatically."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD c=20 r=8 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR c=20 r=8 "XYZ calibration compromised. Front calibration points not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR c=20 r=8 "XYZ calibration compromised. Left front calibration point not reachable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR c=20 r=8 "XYZ calibration compromised. Right front calibration point not reachable."
|
||||
MSG_BEGIN_FILE_LIST c=0 r=0 "Begin file list"
|
||||
MSG_CALIBRATE_BED c=0 r=0 "Calibrate XYZ"
|
||||
MSG_CALIBRATE_BED_RESET c=0 r=0 "Reset XYZ calibr."
|
||||
MSG_CALIBRATE_E c=20 r=1 "Calibrate E"
|
||||
MSG_CALIBRATE_PINDA c=17 r=1 "Calibrate"
|
||||
MSG_CALIBRATION_PINDA_MENU c=17 r=1 "Temp. calibration"
|
||||
MSG_CLEAN_NOZZLE_E c=20 r=8 "E calibration finished. Please clean the nozzle. Click when done."
|
||||
MSG_CNG_SDCARD c=0 r=0 "Change SD card"
|
||||
MSG_CONFIGURATION_VER c=0 r=0 " Last Updated: "
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP c=20 r=2 "Are left and right Z~carriages all up?"
|
||||
MSG_CORRECTLY c=20 r=0 "Changed correctly?"
|
||||
MSG_CRASH_DET_ONLY_IN_NORMAL c=20 r=4 "\x1b[2JCrash detection can\x1b[1;0Hbe turned on only in\x1b[2;0HNormal mode"
|
||||
MSG_CRASH_DET_STEALTH_FORCE_OFF c=20 r=4 "\x1b[2JWARNING:\x1b[1;0HCrash detection\x1b[2;0Hdisabled in\x1b[3;0HStealth mode"
|
||||
MSG_CURRENT c=19 r=1 "Current"
|
||||
MSG_DATE c=17 r=1 "Date:"
|
||||
MSG_DEFAULT_SETTINGS_LOADED c=20 r=4 "Old settings found. Default PID, Esteps etc. will be set."
|
||||
MSG_DISABLE_STEPPERS c=0 r=0 "Disable steppers"
|
||||
MSG_DWELL c=0 r=0 "Sleep..."
|
||||
MSG_E_CAL_KNOB c=20 r=8 "Rotate knob until mark reaches extruder body. Click when done."
|
||||
MSG_END_FILE_LIST c=0 r=0 "End file list"
|
||||
MSG_ERR_COLD_EXTRUDE_STOP c=0 r=0 " cold extrusion prevented"
|
||||
MSG_ERR_CHECKSUM_MISMATCH c=0 r=0 "checksum mismatch, Last Line: "
|
||||
MSG_ERR_KILLED c=0 r=0 "Printer halted. kill() called!"
|
||||
MSG_ERR_NO_CHECKSUM c=0 r=0 "No Checksum with line number, Last Line: "
|
||||
MSG_ERR_NO_THERMISTORS c=0 r=0 "No thermistors - no temperature"
|
||||
MSG_EXTRUDER_1 c=17 r=1 "Extruder 1"
|
||||
MSG_EXTRUDER_2 c=17 r=1 "Extruder 2"
|
||||
MSG_EXTRUDER_3 c=17 r=1 "Extruder 3"
|
||||
MSG_EXTRUDER_4 c=17 r=1 "Extruder 4"
|
||||
MSG_EXTRUDER_CORRECTION c=9 r=0 "E-correct"
|
||||
MSG_EXTRUDER_CORRECTION_OFF c=6 r=0 " [off"
|
||||
MSG_FACTOR c=0 r=0 " \002 Fact"
|
||||
MSG_FANS_CHECK_OFF c=17 r=1 "Fans check [off]"
|
||||
MSG_FANS_CHECK_ON c=17 r=1 "Fans check [on]"
|
||||
MSG_FILAMENT_SENSOR c=20 r=0 "Filament sensor"
|
||||
MSG_FILE_CNT c=20 r=4 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
|
||||
MSG_FILE_INCOMPLETE c=20 r=2 "File incomplete. Continue anyway?"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION c=20 r=0 "Iteration "
|
||||
MSG_FLOW c=0 r=0 "Flow"
|
||||
MSG_FORCE_SELFTEST c=20 r=8 "Selftest will be run to calibrate accurate sensorless rehoming."
|
||||
MSG_FREE_MEMORY c=0 r=0 " Free Memory: "
|
||||
MSG_FSENS_AUTOLOAD_OFF c=17 r=1 "F. autoload [off]"
|
||||
MSG_FSENS_AUTOLOAD_ON c=17 r=1 "F. autoload [on]"
|
||||
MSG_FSENS_NOT_RESPONDING c=20 r=4 "ERROR: Filament sensor is not responding, please check connection."
|
||||
MSG_FSENSOR_NA c=0 r=0 "Fil. sensor [N/A]"
|
||||
MSG_FW_VERSION_ALPHA c=20 r=8 "You are using firmware alpha version. This is development version. Using this version is not recommended and may cause printer damage."
|
||||
MSG_FW_VERSION_BETA c=20 r=8 "You are using firmware beta version. This is development version. Using this version is not recommended and may cause printer damage."
|
||||
MSG_FW_VERSION_UNKNOWN c=20 r=8 "WARNING: This is an unofficial, unsupported build. Use at your own risk!"
|
||||
MSG_HOMEYZ_DONE c=0 r=0 "Calibration done"
|
||||
MSG_HOMEYZ_PROGRESS c=0 r=0 "Calibrating Z"
|
||||
MSG_CHANGE_EXTR c=20 r=1 "Change extruder"
|
||||
MSG_CHANGE_SUCCESS c=0 r=0 "Change success!"
|
||||
MSG_CHANGED_BOTH c=20 r=4 "Warning: both printer type and motherboard type changed."
|
||||
MSG_CHANGED_MOTHERBOARD c=20 r=4 "Warning: motherboard type changed."
|
||||
MSG_CHANGED_PRINTER c=20 r=4 "Warning: printer type changed."
|
||||
MSG_CHANGING_FILAMENT c=20 r=0 "Changing filament!"
|
||||
MSG_CHECK_IDLER c=20 r=4 "Please open idler and remove filament manually."
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 c=60 r=0 "Improving bed calibration point"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14 r=0 " of 4"
|
||||
MSG_INFO_EXTRUDER c=15 r=1 "Extruder info"
|
||||
MSG_INFO_NOZZLE_FAN c=11 r=1 "Nozzle FAN:"
|
||||
MSG_INFO_PRINT_FAN c=11 r=1 "Print FAN: "
|
||||
MSG_INIT_SDCARD c=0 r=0 "Init. SD card"
|
||||
MSG_INSERT_FILAMENT c=20 r=0 "Insert filament"
|
||||
MSG_KILLED c=0 r=0 "KILLED. "
|
||||
MSG_LANGUAGE_SELECT c=0 r=0 "Select language"
|
||||
MSG_LEFT c=12 r=1 "Left:"
|
||||
MSG_LOAD_ALL c=0 r=0 "Load all"
|
||||
MSG_LOAD_FILAMENT_1 c=17 r=0 "Load filament 1"
|
||||
MSG_LOAD_FILAMENT_2 c=17 r=0 "Load filament 2"
|
||||
MSG_LOAD_FILAMENT_3 c=17 r=0 "Load filament 3"
|
||||
MSG_LOAD_FILAMENT_4 c=17 r=0 "Load filament 4"
|
||||
MSG_LOADING_COLOR c=0 r=0 "Loading color"
|
||||
MSG_LOOSE_PULLEY c=20 r=1 "Loose pulley"
|
||||
MSG_M104_INVALID_EXTRUDER c=0 r=0 "M104 Invalid extruder "
|
||||
MSG_M105_INVALID_EXTRUDER c=0 r=0 "M105 Invalid extruder "
|
||||
MSG_M109_INVALID_EXTRUDER c=0 r=0 "M109 Invalid extruder "
|
||||
MSG_M119_REPORT c=0 r=0 "Reporting endstop status"
|
||||
MSG_M200_INVALID_EXTRUDER c=0 r=0 "M200 Invalid extruder "
|
||||
MSG_M218_INVALID_EXTRUDER c=0 r=0 "M218 Invalid extruder "
|
||||
MSG_M221_INVALID_EXTRUDER c=0 r=0 "M221 Invalid extruder "
|
||||
MSG_MARK_FIL c=20 r=8 "Mark filament 100mm from extruder body. Click when done."
|
||||
MSG_MAX c=0 r=0 " \002 Max"
|
||||
MSG_MEASURED_OFFSET c=0 r=0 "[0;0] point offset"
|
||||
MSG_MEASURED_SKEW c=15 r=1 "Measured skew:"
|
||||
MSG_MENU_BELT_STATUS c=15 r=1 "Belt status"
|
||||
MSG_MENU_TEMPERATURES c=15 r=1 "Temperatures"
|
||||
MSG_MENU_VOLTAGES c=15 r=1 "Voltages"
|
||||
MSG_MESH_BED_LEVELING c=0 r=0 "Mesh Bed Leveling"
|
||||
MSG_MIN c=0 r=0 " \002 Min"
|
||||
MSG_MOVE_AXIS c=0 r=0 "Move axis"
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP c=20 r=8 "Calibrating XYZ. Rotate the knob to move the Z carriage up to the end stoppers. Click when done."
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z c=20 r=8 "Calibrating Z. Rotate the knob to move the Z carriage up to the end stoppers. Click when done."
|
||||
MSG_MOVE_E c=0 r=0 "Extruder"
|
||||
MSG_MOVE_X c=0 r=0 "Move X"
|
||||
MSG_MOVE_Y c=0 r=0 "Move Y"
|
||||
MSG_MOVE_Z c=0 r=0 "Move Z"
|
||||
MSG_NEW_FIRMWARE_AVAILABLE c=20 r=2 "New firmware version available:"
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE c=20 r=0 "Please upgrade."
|
||||
MSG_NO_CARD c=0 r=0 "No SD card"
|
||||
MSG_NO_MOVE c=0 r=0 "No move."
|
||||
MSG_NOT_COLOR c=0 r=0 "Color not correct"
|
||||
MSG_NOT_LOADED c=19 r=0 "Filament not loaded"
|
||||
MSG_NOZZLE1 c=0 r=0 "Nozzle2"
|
||||
MSG_NOZZLE2 c=0 r=0 "Nozzle3"
|
||||
MSG_PAUSE_PRINT c=0 r=0 "Pause print"
|
||||
MSG_PICK_Z c=0 r=0 "Pick print"
|
||||
MSG_PID_EXTRUDER c=17 r=1 "PID calibration"
|
||||
MSG_PID_FINISHED c=20 r=1 "PID cal. finished"
|
||||
MSG_PID_RUNNING c=20 r=1 "PID cal. "
|
||||
MSG_PINDA_NOT_CALIBRATED c=20 r=4 "Temperature calibration has not been run yet"
|
||||
MSG_PINDA_PREHEAT c=20 r=1 "PINDA Heating"
|
||||
MSG_PLA_FILAMENT_LOADED c=20 r=2 "Is PLA filament loaded?"
|
||||
MSG_PLANNER_BUFFER_BYTES c=0 r=0 " PlannerBufferBytes: "
|
||||
MSG_PLEASE_LOAD_PLA c=20 r=4 "Please load PLA filament first."
|
||||
MSG_PREHEAT c=0 r=0 "Preheat"
|
||||
MSG_PREPARE_FILAMENT c=20 r=1 "Prepare new filament"
|
||||
MSG_PRESS c=20 r=0 "and press the knob"
|
||||
MSG_PRESS_TO_PREHEAT c=20 r=4 "Press knob to preheat nozzle and continue."
|
||||
MSG_PRINT_PAUSED c=20 r=1 "Print paused"
|
||||
MSG_PRINTER_DISCONNECTED c=20 r=1 "Printer disconnected"
|
||||
MSG_PRUSA3D c=0 r=0 "prusa3d.com"
|
||||
MSG_PRUSA3D_FORUM c=0 r=0 "forum.prusa3d.com"
|
||||
MSG_PRUSA3D_HOWTO c=0 r=0 "howto.prusa3d.com"
|
||||
MSG_RECOVERING_PRINT c=20 r=1 "Recovering print "
|
||||
MSG_RESEND c=0 r=0 "Resend: "
|
||||
MSG_RESUME_PRINT c=0 r=0 "Resume print"
|
||||
MSG_RESUMING c=0 r=0 "Resuming print"
|
||||
MSG_RESUMING_PRINT c=20 r=1 "Resuming print"
|
||||
MSG_RIGHT c=12 r=1 "Right:"
|
||||
MSG_SD_CANT_ENTER_SUBDIR c=0 r=0 "Cannot enter subdir: "
|
||||
MSG_SD_CANT_OPEN_SUBDIR c=0 r=0 "Cannot open subdir"
|
||||
MSG_SD_CARD_OK c=0 r=0 "SD card ok"
|
||||
MSG_SD_FILE_OPENED c=0 r=0 "File opened: "
|
||||
MSG_SD_FILE_SELECTED c=0 r=0 "File selected"
|
||||
MSG_SD_INIT_FAIL c=0 r=0 "SD init fail"
|
||||
MSG_SD_INSERTED c=0 r=0 "Card inserted"
|
||||
MSG_SD_OPENROOT_FAIL c=0 r=0 "openRoot failed"
|
||||
MSG_SD_PRINTING_BYTE c=0 r=0 "SD printing byte "
|
||||
MSG_SD_REMOVED c=0 r=0 "Card removed"
|
||||
MSG_SD_VOL_INIT_FAIL c=0 r=0 "volume.init failed"
|
||||
MSG_SD_WRITE_TO_FILE c=0 r=0 "Writing to file: "
|
||||
MSG_SECOND_SERIAL_OFF c=17 r=1 "RPi port [off]"
|
||||
MSG_SECOND_SERIAL_ON c=17 r=1 "RPi port [on]"
|
||||
MSG_SELFTEST c=0 r=0 "Selftest "
|
||||
MSG_SELFTEST_AXIS c=0 r=0 "Axis"
|
||||
MSG_SELFTEST_AXIS_LENGTH c=0 r=0 "Axis length"
|
||||
MSG_SELFTEST_BEDHEATER c=0 r=0 "Bed / Heater"
|
||||
MSG_SELFTEST_ENDSTOP c=0 r=0 "Endstop"
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1 "Endstop not hit"
|
||||
MSG_SELFTEST_ENDSTOPS c=0 r=0 "Endstops"
|
||||
MSG_SELFTEST_ERROR c=0 r=0 "Selftest error !"
|
||||
MSG_SELFTEST_EXTRUDER_FAN_SPEED c=18 r=0 "Extruder fan:"
|
||||
MSG_SELFTEST_FANS c=0 r=0 "Front/left fans"
|
||||
MSG_SELFTEST_FILAMENT_SENSOR c=18 r=0 "Filament sensor:"
|
||||
MSG_SELFTEST_HEATERTHERMISTOR c=0 r=0 "Heater/Thermistor"
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT c=20 r=0 "All correct "
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS c=20 r=0 "Checking endstops"
|
||||
MSG_SELFTEST_CHECK_HOTEND c=20 r=0 "Checking hotend "
|
||||
MSG_SELFTEST_CHECK_X c=20 r=0 "Checking X axis "
|
||||
MSG_SELFTEST_CHECK_Y c=20 r=0 "Checking Y axis "
|
||||
MSG_SELFTEST_CHECK_Z c=20 r=0 "Checking Z axis "
|
||||
MSG_SELFTEST_NOTCONNECTED c=0 r=0 "Not connected"
|
||||
MSG_SELFTEST_OK c=0 r=0 "Self test OK"
|
||||
MSG_SELFTEST_PLEASECHECK c=0 r=0 "Please check :"
|
||||
MSG_SELFTEST_PRINT_FAN_SPEED c=18 r=0 "Print fan:"
|
||||
MSG_SELFTEST_START c=20 r=0 "Self test start "
|
||||
MSG_SELFTEST_SWAPPED c=0 r=0 "Swapped"
|
||||
MSG_SET_TEMPERATURE c=19 r=1 "Set temperature:"
|
||||
MSG_SEVERE_SKEW c=15 r=1 "Severe skew:"
|
||||
MSG_SHOW_END_STOPS c=17 r=1 "Show end stops"
|
||||
MSG_SLIGHT_SKEW c=15 r=1 "Slight skew:"
|
||||
MSG_SORT_ALPHA c=17 r=1 "Sort: [Alphabet]"
|
||||
MSG_SORT_NONE c=17 r=1 "Sort: [None]"
|
||||
MSG_SORT_TIME c=17 r=1 "Sort: [Time]"
|
||||
MSG_SORTING c=20 r=1 "Sorting files"
|
||||
MSG_SPEED c=0 r=0 "Speed"
|
||||
MSG_STACK_ERROR c=20 r=4 "Error - static memory has been overwritten"
|
||||
MSG_STATISTICS c=0 r=0 "Statistics "
|
||||
MSG_STATS_FILAMENTUSED c=20 r=0 "Filament used: "
|
||||
MSG_STATS_PRINTTIME c=20 r=0 "Print time: "
|
||||
MSG_STATS_TOTALFILAMENT c=20 r=0 "Total filament :"
|
||||
MSG_STATS_TOTALPRINTTIME c=20 r=0 "Total print time :"
|
||||
MSG_STEPPER_TOO_HIGH c=0 r=0 "Steprate too high: "
|
||||
MSG_SUPPORT c=0 r=0 "Support"
|
||||
MSG_TEMP_CAL_FAILED c=20 r=8 "Temperature calibration failed"
|
||||
MSG_TEMP_CAL_WARNING c=20 r=4 "Stable ambient temperature 21-26C is needed a rigid stand is required."
|
||||
MSG_TEMP_CALIBRATION_OFF c=20 r=1 "Temp. cal. [off]"
|
||||
MSG_TEMP_CALIBRATION_ON c=20 r=1 "Temp. cal. [on]"
|
||||
MSG_TEMPERATURE c=0 r=0 "Temperature"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1 "SD card [normal]"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1 "SD card [FlshAir]"
|
||||
MSG_TUNE c=0 r=0 "Tune"
|
||||
MSG_UNLOAD_ALL c=0 r=0 "Unload all"
|
||||
MSG_UNLOAD_FILAMENT_1 c=17 r=0 "Unload filament 1"
|
||||
MSG_UNLOAD_FILAMENT_2 c=17 r=0 "Unload filament 2"
|
||||
MSG_UNLOAD_FILAMENT_3 c=17 r=0 "Unload filament 3"
|
||||
MSG_UNLOAD_FILAMENT_4 c=17 r=0 "Unload filament 4"
|
||||
MSG_UNLOAD_SUCCESSFUL c=20 r=2 "Was filament unload successful?"
|
||||
MSG_USED c=19 r=1 "Used during print"
|
||||
MSG_USERWAIT c=0 r=0 "Wait for user..."
|
||||
MSG_V2_CALIBRATION c=17 r=1 "First layer cal."
|
||||
MSG_WAITING_TEMP c=20 r=3 "Waiting for nozzle and bed cooling"
|
||||
MSG_WAITING_TEMP_PINDA c=20 r=3 "Waiting for PINDA probe cooling"
|
||||
MSG_WIZARD c=17 r=1 "Wizard"
|
||||
MSG_WIZARD_CLEAN_HEATBED c=20 r=8 "Please clean heatbed and then press the knob."
|
||||
MSG_WIZARD_FILAMENT_LOADED c=20 r=2 "Is filament loaded?"
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT c=20 r=8 "Please load PLA filament and then resume Wizard by rebooting the printer."
|
||||
MSG_WIZARD_LOAD_FILAMENT c=20 r=8 "Please insert PLA filament to the extruder, then press knob to load it."
|
||||
MSG_WIZARD_PLA_FILAMENT c=20 r=2 "Is it PLA filament?"
|
||||
MSG_WIZARD_REPEAT_V2_CAL c=20 r=7 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
|
||||
MSG_WIZARD_RERUN c=20 r=7 "Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
MSG_WIZARD_SELFTEST c=20 r=8 "First, I will run the selftest to check most common assembly problems."
|
||||
MSG_WIZARD_V2_CAL c=20 r=8 "Now I will calibrate distance between tip of the nozzle and heatbed surface."
|
||||
MSG_WIZARD_V2_CAL_2 c=20 r=12 "I will start to print line and you will gradually lower the nozzle by rotating the knob, until you reach optimal height. Check the pictures in our handbook in chapter Calibration."
|
||||
MSG_WIZARD_WELCOME c=20 r=7 "Hi, I am your Original Prusa i3 printer. Would you like me to guide you through the setup process?"
|
||||
MSG_WIZARD_WILL_PREHEAT c=20 r=4 "Now I will preheat nozzle for PLA."
|
||||
MSG_WIZARD_XYZ_CAL c=20 r=8 "I will run xyz calibration now. It will take approx. 12 mins."
|
||||
MSG_WIZARD_Z_CAL c=20 r=8 "I will run z calibration now."
|
||||
MSG_XYZ_DETAILS c=19 r=1 "XYZ cal. details"
|
||||
MSG_Y_DISTANCE_FROM_MIN c=20 r=1 "Y distance from min:"
|
289
lang_upgrade/msgs_es.txt
Normal file
289
lang_upgrade/msgs_es.txt
Normal file
@ -0,0 +1,289 @@
|
||||
MSG_ADJUSTZ "Ajustar Eje Z"
|
||||
MSG_ALL "Todos"
|
||||
MSG_AUTO_HOME "Llevar al origen"
|
||||
MSG_BABYSTEP_X "Babystep X"
|
||||
MSG_BABYSTEP_Y "Babystep Y"
|
||||
MSG_BABYSTEP_Z "Micropaso Eje Z"
|
||||
MSG_BABYSTEP_Z_NOT_SET "Distancia entre la punta del nozzle y la superficie de la heatbed aun no fijada. Por favor siga el manual, capitulo First steps, First layer calibration."
|
||||
MSG_BABYSTEPPING_X "Babystepping X"
|
||||
MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
MSG_BABYSTEPPING_Z "Ajustar Z"
|
||||
MSG_BED "Heatbed"
|
||||
MSG_BED_CORRECTION_FRONT "Frontal [um]"
|
||||
MSG_BED_CORRECTION_LEFT "Izquierda [um]"
|
||||
MSG_BED_CORRECTION_MENU "Corr. de la cama"
|
||||
MSG_BED_CORRECTION_REAR "Trasera [um]"
|
||||
MSG_BED_CORRECTION_RESET "Reset"
|
||||
MSG_BED_CORRECTION_RIGHT "Derecha [um]"
|
||||
MSG_BED_DONE "Base preparada"
|
||||
MSG_BED_HEATING "Calentando Base"
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH "Nivelacion fallada. Sensor funciona demasiado temprano. Esperando reset."
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW "Nivelacion fallada. Sensor no funciona. Escombros en nozzle? Esperando reset."
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Nivelacion fallada. Sensor desconectado o cables danados. Esperando reset."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Calibracion XYZ fallada. Puntos frontales no alcanzables."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Calibracion XYZ fallada. Punto frontal izquierdo no alcanzable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Calibracion XYZ fallad. Punto frontal derecho no alcanzable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Calibracion XYZ fallada. Consulta el manual por favor."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Calibracion XYZ ok. Ejes X/Y perpendiculares. Enhorabuena!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Calibracion XYZ fallada. Puntos de calibracion en heatbed no encontrados."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Calibracion XYZ correcta. La inclinacion se corregira automaticamente."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Calibracion XYZ correcta. Los ejes X / Y estan ligeramente inclinados. Buen trabajo!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Calibrazion XYZ comprometida. Puntos frontales no alcanzables."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Calibrazion XYZ comprometida. Punto frontal izquierdo no alcanzable."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Calibrazion XYZ comprometida. Punto frontal derecho no alcanzable."
|
||||
MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
MSG_CALIBRATE_BED "Calibra XYZ"
|
||||
MSG_CALIBRATE_BED_RESET "Reset XYZ calibr."
|
||||
MSG_CALIBRATE_E "Calibrar E"
|
||||
MSG_CALIBRATE_PINDA "Calibrar"
|
||||
MSG_CALIBRATION_PINDA_MENU "Calibracion temp."
|
||||
MSG_CARD_MENU "Menu tarjeta SD"
|
||||
MSG_CLEAN_NOZZLE_E "E calibrado. Limpia nozzle. Haz clic una vez terminado."
|
||||
MSG_CNG_SDCARD "Change SD card"
|
||||
MSG_CONFIGURATION_VER " Last Updated: "
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Carros Z izq./der. estan arriba maximo?"
|
||||
MSG_CONFIRM_NOZZLE_CLEAN "Limpia nozzle para calibracion. Click cuando acabes."
|
||||
MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamentos ajustados. Limpia nozzle para calibracion. Haz clic una vez terminado."
|
||||
MSG_CONTROL "Control"
|
||||
MSG_COOLDOWN "Enfriar"
|
||||
MSG_CORRECTLY "Cambiado correct.?"
|
||||
MSG_CURRENT "Actual"
|
||||
MSG_DISABLE_STEPPERS "Apagar motores"
|
||||
MSG_DWELL "En espera"
|
||||
MSG_E_CAL_KNOB "Rotar el mando hasta que la marca llegue al cuerpo del extrusor. Haz clic una vez terminado."
|
||||
MSG_END_FILE_LIST "End file list"
|
||||
MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
MSG_ENDSTOP_OPEN "open"
|
||||
MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
MSG_Enqueing "enqueing \""
|
||||
MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
MSG_ERROR "ERROR:"
|
||||
MSG_EXTRUDER "Extrusor"
|
||||
MSG_EXTRUDER_1 "Extrusor 1"
|
||||
MSG_EXTRUDER_2 "Extrusor 2"
|
||||
MSG_EXTRUDER_3 "Extrusor 3"
|
||||
MSG_EXTRUDER_4 "Extrusor 4"
|
||||
MSG_FACTOR " \002 Fact"
|
||||
MSG_FAN_SPEED "Velocidad Vent."
|
||||
MSG_FIL_ADJUSTING "Ajustando filamentos. Espera por favor."
|
||||
MSG_FILAMENT_CLEAN "Es el nuevo color nitido?"
|
||||
MSG_FILAMENT_LOADING_T0 "Insertar filamento en el extrusor 1. Haz clic una vez terminado."
|
||||
MSG_FILAMENT_LOADING_T1 "Insertar filamento en el extrusor 2. Haz clic una vez terminado."
|
||||
MSG_FILAMENT_LOADING_T2 "Insertar filamento en el extrusor 3. Haz clic una vez terminado."
|
||||
MSG_FILAMENT_LOADING_T3 "Insertar filamento en el extrusor 4. Haz clic una vez terminado."
|
||||
MSG_FILAMENTCHANGE "Cambiar filamento"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Reiteracion "
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Buscando punto de calibracion heatbed"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " de 4"
|
||||
MSG_FINISHING_MOVEMENTS "Term. movimientos"
|
||||
MSG_FLOW "Flujo"
|
||||
MSG_FLOW0 "Flow 0"
|
||||
MSG_FLOW1 "Flow 1"
|
||||
MSG_FLOW2 "Flow 2"
|
||||
MSG_FOLLOW_CALIBRATION_FLOW "Impresora no esta calibrada todavia. Por favor usa el manual, capitulo First steps, Calibration flow."
|
||||
MSG_FREE_MEMORY " Free Memory: "
|
||||
MSG_HEATING "Calentando..."
|
||||
MSG_HEATING_COMPLETE "Calentamiento final."
|
||||
MSG_HOMEYZ "Calibrar Z"
|
||||
MSG_HOMEYZ_DONE "Calibracion OK"
|
||||
MSG_HOMEYZ_PROGRESS "Calibrando Z"
|
||||
MSG_CHANGE_EXTR "Cambiar extrusor."
|
||||
MSG_CHANGE_SUCCESS "Cambio correcto"
|
||||
MSG_CHANGING_FILAMENT "Cambiando filamento"
|
||||
MSG_CHOOSE_EXTRUDER "Elegir extrusor:"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Mejorando punto de calibracion heatbed"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " de 4"
|
||||
MSG_INIT_SDCARD "Init. SD card"
|
||||
MSG_INSERT_FILAMENT "Introducir filamento"
|
||||
MSG_KILLED "PARADA DE EMERGENCIA"
|
||||
MSG_LANGUAGE_NAME "Espanol"
|
||||
MSG_LANGUAGE_SELECT "Cambiae el idioma"
|
||||
MSG_LOAD_ALL "Intr. todos fil."
|
||||
MSG_LOAD_EPROM "Load memory"
|
||||
MSG_LOAD_FILAMENT "Introducir filam."
|
||||
MSG_LOAD_FILAMENT_1 "Introducir fil. 1"
|
||||
MSG_LOAD_FILAMENT_2 "Introducir fil. 2"
|
||||
MSG_LOAD_FILAMENT_3 "Introducir fil. 3"
|
||||
MSG_LOAD_FILAMENT_4 "Introducir fil. 4"
|
||||
MSG_LOADING_COLOR "Cambiando color"
|
||||
MSG_LOADING_FILAMENT "Introduciendo filam."
|
||||
MSG_LOOSE_PULLEY "Polea suelta"
|
||||
MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
MSG_M117_V2_CALIBRATION "M117 Cal. primera cap."
|
||||
MSG_M119_REPORT "Reporting endstop status"
|
||||
MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
MSG_MAIN "Menu principal"
|
||||
MSG_MARK_FIL "Marque el filamento 100 mm por encima del final del extrusor. Haz clic una vez terminado."
|
||||
MSG_MAX " \002 Max"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Midiendo altura del punto de calibracion"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " de 9"
|
||||
MSG_MENU_CALIBRATION "Calibracion"
|
||||
MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
|
||||
MSG_MIN " \002 Min"
|
||||
MSG_MOTION "Motion"
|
||||
MSG_MOVE_AXIS "Mover ejes"
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP "Calibrando XYZ. Gira el boton para subir el extrusor hasta tocar los topes superiores. Despues haz clic."
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Calibrando Z. Gira el boton para subir el extrusor hasta tocar los topes superiores. Despues haz clic."
|
||||
MSG_MOVE_E "Extruir"
|
||||
MSG_MOVE_X "Mover X"
|
||||
MSG_MOVE_Y "Mover Y"
|
||||
MSG_MOVE_Z "Mover Z"
|
||||
MSG_NEW_FIRMWARE_AVAILABLE "Nuevo firmware disponible:"
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Actualizar por favor"
|
||||
MSG_NO "No"
|
||||
MSG_NO_CARD "No hay tarjeta SD"
|
||||
MSG_NO_MOVE "Sin movimiento"
|
||||
MSG_NOT_COLOR "Color no homogeneo"
|
||||
MSG_NOT_LOADED "Fil. no introducido"
|
||||
MSG_NOZZLE "Nozzle"
|
||||
MSG_NOZZLE1 "Nozzle2"
|
||||
MSG_NOZZLE2 "Nozzle3"
|
||||
MSG_OK "ok"
|
||||
MSG_PAPER "Colocar una hoja de papel sobre la superficie de impresion durante la calibracion de los primeros 4 puntos. Si la boquilla mueve el papel, apagar impresora inmediatamente."
|
||||
MSG_PAUSE_PRINT "Pausar impresion"
|
||||
MSG_PICK_Z "Esc. Modelo Adecuado"
|
||||
MSG_PID_EXTRUDER "Calibracion PID"
|
||||
MSG_PID_FINISHED "Cal. PID terminada"
|
||||
MSG_PID_RUNNING "Cal. PID "
|
||||
MSG_PINDA_NOT_CALIBRATED "La temperatura de calibracion no ha sido ajustada"
|
||||
MSG_PINDA_PREHEAT "Calentando PINDA"
|
||||
MSG_PLA_FILAMENT_LOADED "Esta el filamento PLA cargado?"
|
||||
MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
MSG_PLEASE_LOAD_PLA "Carga el filamento PLA primero por favor."
|
||||
MSG_PLEASE_WAIT "Por Favor Esperar"
|
||||
MSG_POWERUP "PowerUp"
|
||||
MSG_PREHEAT "Precalentar"
|
||||
MSG_PREHEAT_NOZZLE "Precalentar extrusor"
|
||||
MSG_PREPARE_FILAMENT "Preparar filamento"
|
||||
MSG_PREPARE_FILAMENT "Preparar filamento"
|
||||
MSG_PRESS "Haz clic"
|
||||
MSG_PRINT_ABORTED "Impresion cancelada"
|
||||
MSG_PRINT_PAUSED "Impresion en pausa"
|
||||
MSG_PRUSA3D "prusa3d.com"
|
||||
MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
MSG_REBOOT "Reiniciar impresora"
|
||||
MSG_RECTRACT "Rectract"
|
||||
MSG_REFRESH "\xF8" "Refresh"
|
||||
MSG_RESEND "Resend: "
|
||||
MSG_RESTORE_FAILSAFE "Restore failsafe"
|
||||
MSG_RESUME_PRINT "Reanudar impres."
|
||||
MSG_RESUMING "Resumiendo impresion"
|
||||
MSG_RESUMING_PRINT "Reanudar impresion"
|
||||
MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
MSG_SD_CARD_OK "SD card ok"
|
||||
MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
MSG_SD_FILE_OPENED "File opened: "
|
||||
MSG_SD_FILE_SELECTED "File selected"
|
||||
MSG_SD_INIT_FAIL "SD init fail"
|
||||
MSG_SD_INSERTED "Tarjeta insertada"
|
||||
MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
MSG_SD_REMOVED "Tarjeta retirada"
|
||||
MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
MSG_SELFTEST "Selftest"
|
||||
MSG_SELFTEST_BEDHEATER "Heatbed"
|
||||
MSG_SELFTEST_COOLING_FAN "Vent. frontal?"
|
||||
MSG_SELFTEST_ENDSTOP "Tope final"
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT "Tope no alcanzado"
|
||||
MSG_SELFTEST_ENDSTOPS "Topes finales"
|
||||
MSG_SELFTEST_ERROR "Autotest error!"
|
||||
MSG_SELFTEST_EXTRUDER_FAN "Vent. izquierdo?"
|
||||
MSG_SELFTEST_FAILED "Fallo Selftest"
|
||||
MSG_SELFTEST_FAN "Test ventiladores"
|
||||
MSG_SELFTEST_FAN_NO "Ventilador no gira"
|
||||
MSG_SELFTEST_FAN_YES "Ventilador gira"
|
||||
MSG_SELFTEST_HEATERTHERMISTOR "Hotend"
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT "Todo bien"
|
||||
MSG_SELFTEST_CHECK_BED "Control heatbed"
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS "Control topes"
|
||||
MSG_SELFTEST_CHECK_HOTEND "Control hotend "
|
||||
MSG_SELFTEST_CHECK_X "Control tope X"
|
||||
MSG_SELFTEST_CHECK_Y "Control tope Y"
|
||||
MSG_SELFTEST_CHECK_Z "Control tope Z"
|
||||
MSG_SELFTEST_MOTOR "Motor"
|
||||
MSG_SELFTEST_NOTCONNECTED "No hay conexion "
|
||||
MSG_SELFTEST_OK "Self test OK"
|
||||
MSG_SELFTEST_PLEASECHECK "Controla :"
|
||||
MSG_SELFTEST_START "Inicio Selftest"
|
||||
MSG_SELFTEST_WIRINGERROR "Error de conexion"
|
||||
MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
MSG_SET_HOME_OFFSETS "Set home offsets"
|
||||
MSG_SET_ORIGIN "Set origin"
|
||||
MSG_SET_TEMPERATURE "Establecer temp.:"
|
||||
MSG_SETTINGS "Configuracion"
|
||||
MSG_SHOW_END_STOPS "Ensena tope final"
|
||||
MSG_SILENT_MODE_OFF "Modo [rend.pleno]"
|
||||
MSG_SILENT_MODE_ON "Modo [silencio]"
|
||||
MSG_SPEED "Velocidad"
|
||||
MSG_STATISTICS "Estadisticas "
|
||||
MSG_STATS_FILAMENTUSED "Filamento usado: "
|
||||
MSG_STATS_PRINTTIME "Tiempo de imp.:"
|
||||
MSG_STATS_TOTALFILAMENT "Filamento total:"
|
||||
MSG_STATS_TOTALPRINTTIME "Tiempo total :"
|
||||
MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
MSG_STOP_PRINT "Detener impresion"
|
||||
MSG_STOPPED "PARADA"
|
||||
MSG_STORE_EPROM "Store memory"
|
||||
MSG_SUPPORT "Soporte"
|
||||
MSG_SWITCH_PS_OFF "Switch power off"
|
||||
MSG_SWITCH_PS_ON "Switch power on"
|
||||
MSG_TAKE_EFFECT " para aplicar cambios"
|
||||
MSG_TEMP_CALIBRATION "Cal. temp. "
|
||||
MSG_TEMP_CALIBRATION_DONE "Calibracon temperatura terminada. Haz clic para continuar."
|
||||
MSG_TEMP_CALIBRATION_OFF "Cal. temp. [OFF]"
|
||||
MSG_TEMP_CALIBRATION_ON "Cal. temp. [ON]"
|
||||
MSG_TEMPERATURE "Temperatura"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
|
||||
MSG_TUNE "Ajustar"
|
||||
MSG_UNLOAD_ALL "Soltar todos fil."
|
||||
MSG_UNLOAD_FILAMENT "Soltar filamento"
|
||||
MSG_UNLOAD_FILAMENT_1 "Soltar fil. 1"
|
||||
MSG_UNLOAD_FILAMENT_2 "Soltar fil. 2"
|
||||
MSG_UNLOAD_FILAMENT_3 "Soltar fil. 3"
|
||||
MSG_UNLOAD_FILAMENT_4 "Soltar fil. 4"
|
||||
MSG_UNLOADING_FILAMENT "Soltando filamento"
|
||||
MSG_USB_PRINTING "Impresion con USB "
|
||||
MSG_USED "Usado en impresion"
|
||||
MSG_USERWAIT "Esperando ordenes"
|
||||
MSG_V2_CALIBRATION "Cal. primera cap."
|
||||
MSG_VOLUMETRIC "Filament"
|
||||
MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
MSG_WAITING_TEMP "Esperando enfriamiento de heatbed y extrusor."
|
||||
MSG_WATCH "Monitorizar"
|
||||
MSG_WIZARD "Wizard"
|
||||
MSG_WIZARD_CALIBRATION_FAILED "Lee el manual y resuelve el problema. Despues, reinicia la impresora y continua con el Wizard"
|
||||
MSG_WIZARD_CLEAN_HEATBED "Limpia la superficie de la heatbed, por favor, y haz clic"
|
||||
MSG_WIZARD_DONE "Terminado! Feliz impresion!"
|
||||
MSG_WIZARD_FILAMENT_LOADED "Esta el filamento cargado?"
|
||||
MSG_WIZARD_HEATING "Precalentando nozzle. Espera por favor."
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT "Carga filamento PLA, por favor, y reinicia la impresora para continuar con el Wizard"
|
||||
MSG_WIZARD_LOAD_FILAMENT "Inserta, por favor, filamento PLA en el extrusor. Despues haz clic para cargarlo."
|
||||
MSG_WIZARD_PLA_FILAMENT "Es el filamento PLA?"
|
||||
MSG_WIZARD_QUIT "Siempre puedes acceder al asistente desde Calibracion -> Wizard"
|
||||
MSG_WIZARD_REPEAT_V2_CAL "Quieres repetir el ultimo paso para reajustar la distancia nozzle-heatbed?"
|
||||
MSG_WIZARD_RERUN "Ejecutar el Wizard borrara los valores de calibracion actuales y comenzara de nuevo. Continuar?"
|
||||
MSG_WIZARD_SELFTEST "Primero, hare el Selftest para comprobar los problemas de montaje mas comunes."
|
||||
MSG_WIZARD_V2_CAL "Voy a calibrar la distancia entre la punta del nozzle y la superficie de la heatbed."
|
||||
MSG_WIZARD_V2_CAL_2 "Voy a comenzar a imprimir la linea y tu bajaras el nozzle gradualmente al rotar el mando, hasta que llegues a la altura optima. Mira las imagenes del capitulo Calibracion en el manual."
|
||||
MSG_WIZARD_WELCOME "Hola, soy tu impresora Original Prusa i3. Quieres que te guie a traves de la configuracion?"
|
||||
MSG_WIZARD_WILL_PREHEAT "Voy a precalentar el nozzle para PLA ahora."
|
||||
MSG_WIZARD_XYZ_CAL "Hare la calibracion XYZ. Tardara 12 min. aproximadamente."
|
||||
MSG_WIZARD_Z_CAL "Voy a hacer Calibracion Z ahora."
|
||||
MSG_YES "Si"
|
||||
WELCOME_MSG CUSTOM_MENDEL_NAME " prep."
|
294
lang_upgrade/msgs_it.txt
Normal file
294
lang_upgrade/msgs_it.txt
Normal file
@ -0,0 +1,294 @@
|
||||
MSG_ADJUSTZ "Autoregolare Z?"
|
||||
MSG_ALL "Tutti"
|
||||
MSG_AUTO_HOME "Trova origine"
|
||||
MSG_BABYSTEP_X "Babystep X"
|
||||
MSG_BABYSTEP_Y "Babystep Y"
|
||||
MSG_BABYSTEP_Z "Compensazione Z"
|
||||
MSG_BABYSTEP_Z_NOT_SET "Distanza tra la punta dell'ugello e la superficie del letto non ancora imposta. Si prega di seguire il manuale, capitolo First steps, sezione First layer calibration."
|
||||
MSG_BABYSTEPPING_X "Babystepping X"
|
||||
MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
MSG_BABYSTEPPING_Z "Compensazione Z"
|
||||
MSG_BED "Letto"
|
||||
MSG_BED_CORRECTION_FRONT "Fronte [um]"
|
||||
MSG_BED_CORRECTION_LEFT "Sinistra [um]"
|
||||
MSG_BED_CORRECTION_MENU "Correz. liv.letto"
|
||||
MSG_BED_CORRECTION_REAR "Retro [um]"
|
||||
MSG_BED_CORRECTION_RESET "Reset"
|
||||
MSG_BED_CORRECTION_RIGHT "Destra [um]"
|
||||
MSG_BED_DONE "Piatto fatto."
|
||||
MSG_BED_HEATING "Riscald. letto"
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH "Livellamento letto fallito.Risp sensore troppo prestoIn attesa di reset."
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW "Livellamento letto fallito.NoRispSensor Residui su ugello? In attesa di reset."
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Livellamento letto fallito. Sensore discon. o Cavo Dann. In attesa di reset."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Calibrazione XYZ fallita. Punti anteriori non raggiungibili."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Calibrazione XYZ fallita. Punto anteriore sinistro non raggiungibile."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Calibrazione XYZ fallita. Punto anteriore destro non raggiungibile."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Calibrazione XYZ fallita. Si prega di consultare il manuale."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Calibrazione XYZ OK. Gli assi X/Y sono perpendicolari. Complimenti!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Calibrazione XYZ fallita. Il punto di calibrazione sul letto non e' stato trovato."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Calibrazion XYZ corretta. La distorsione verra' automaticamente compensata."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Calibrazion XYZ corretta. Assi X/Y leggermente storti. Ben fatto!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Calibrazione XYZ compromessa. Punti anteriori non raggiungibili."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Calibrazione XYZ compromessa. Punto anteriore sinistro non raggiungibile."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Calibrazione XYZ compromessa. Punto anteriore destro non raggiungibile."
|
||||
MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
MSG_CALIBRATE_BED "Calibra XYZ"
|
||||
MSG_CALIBRATE_BED_RESET "Reset XYZ calibr."
|
||||
MSG_CALIBRATE_E "Calibra E"
|
||||
MSG_CALIBRATE_PINDA "Calibrare"
|
||||
MSG_CALIBRATION_PINDA_MENU "Taratura temp."
|
||||
MSG_CARD_MENU "Stampa da SD"
|
||||
MSG_CLEAN_NOZZLE_E "Calibrazione E terminata. Si prega di pulire l'ugello. Click per continuare."
|
||||
MSG_CNG_SDCARD "Change SD card"
|
||||
MSG_CONFIGURATION_VER " Last Updated: "
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP "I carrelli Z sin/des sono altezza max?"
|
||||
MSG_CONFIRM_NOZZLE_CLEAN "Pulire l'ugello per la calibrazione, poi fare click."
|
||||
MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "I filamenti sono regolati. Si prega di pulire l'ugello per la calibrazione. Click per continuare."
|
||||
MSG_COOLDOWN "Raffredda"
|
||||
MSG_CORRECTLY "Cambiato corr.?"
|
||||
MSG_CURRENT "Attuale"
|
||||
MSG_DATE "Data"
|
||||
MSG_DISABLE_STEPPERS "Disabilit motori"
|
||||
MSG_DWELL "Sospensione..."
|
||||
MSG_E_CAL_KNOB "Girare la manopola affinche' il segno raggiunga il corpo dell'estrusore. Click per continuare."
|
||||
MSG_END_FILE_LIST "End file list"
|
||||
MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
MSG_ENDSTOP_OPEN "open"
|
||||
MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
MSG_Enqueing "enqueing \""
|
||||
MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
MSG_ERROR "ERRORE:"
|
||||
MSG_EXTRUDER "Estrusore"
|
||||
MSG_EXTRUDER_1 "Estrusore 1"
|
||||
MSG_EXTRUDER_2 "Estrusore 2"
|
||||
MSG_EXTRUDER_3 "Estrusore 3"
|
||||
MSG_EXTRUDER_4 "Estrusore 4"
|
||||
MSG_FAN_SPEED "Velocita vent."
|
||||
MSG_FIL_ADJUSTING "Filamento in fase di regolazione. Attendere prego."
|
||||
MSG_FILAMENT_CLEAN "Il colore e' nitido?"
|
||||
MSG_FILAMENT_LOADING_T0 "Inserire filamento nell'estrusore 1. Click per continuare."
|
||||
MSG_FILAMENT_LOADING_T1 "Inserire filamento nell'estrusore 2. Click per continuare."
|
||||
MSG_FILAMENT_LOADING_T2 "Inserire filamento nell'estrusore 3. Click per continuare."
|
||||
MSG_FILAMENT_LOADING_T3 "Inserire filamento nell'estrusore 4. Click per continuare."
|
||||
MSG_FILAMENTCHANGE "Camb. filamento"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Reiterazione "
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Ricerca del letto punto di calibraz."
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " su 4"
|
||||
MSG_FINISHING_MOVEMENTS "Arresto in corso"
|
||||
MSG_FLOW "Flusso"
|
||||
MSG_FOLLOW_CALIBRATION_FLOW "Stampante ancora non calibrata. Si prega di seguire il manuale, capitolo PRIMI PASSI, sezione della calibrazione."
|
||||
MSG_FREE_MEMORY " Free Memory: "
|
||||
MSG_HEATING "Riscaldamento..."
|
||||
MSG_HEATING_COMPLETE "Riscald. completo"
|
||||
MSG_HOMEYZ "Calibra Z"
|
||||
MSG_HOMEYZ_DONE "Calibrazione OK"
|
||||
MSG_HOMEYZ_PROGRESS "Calibrando Z"
|
||||
MSG_CHANGE_EXTR "Cambio estrusore."
|
||||
MSG_CHANGE_SUCCESS "Cambio riuscito!"
|
||||
MSG_CHANGING_FILAMENT "Cambiando filam."
|
||||
MSG_CHOOSE_EXTRUDER "Seleziona estrusore:"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Perfezion. il letto punto di calibraz."
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " su 4"
|
||||
MSG_INIT_SDCARD "Init. SD card"
|
||||
MSG_INSERT_FILAMENT "Inserire filamento"
|
||||
MSG_KILLED "IN TILT."
|
||||
MSG_LANGUAGE_NAME "Italiano"
|
||||
MSG_LANGUAGE_SELECT "Seleziona lingua"
|
||||
MSG_LEFT "Sinistra:"
|
||||
MSG_LOAD_ALL "Caricare tutti"
|
||||
MSG_LOAD_EPROM "Load memory"
|
||||
MSG_LOAD_FILAMENT "Carica filamento"
|
||||
MSG_LOAD_FILAMENT_1 "Caricare fil. 1"
|
||||
MSG_LOAD_FILAMENT_2 "Caricare fil. 2"
|
||||
MSG_LOAD_FILAMENT_3 "Caricare fil. 3"
|
||||
MSG_LOAD_FILAMENT_4 "Caricare fil. 4"
|
||||
MSG_LOADING_COLOR "Caricando colore"
|
||||
MSG_LOADING_FILAMENT "Caricando filam."
|
||||
MSG_LOOSE_PULLEY "Puleggia lenta"
|
||||
MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
MSG_M117_V2_CALIBRATION "M117 Cal. primo layer."
|
||||
MSG_M119_REPORT "Reporting endstop status"
|
||||
MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
MSG_MAIN "Menu principale"
|
||||
MSG_MARK_FIL "Segnare il filamento a 100 mm di distanza dal corpo dell'estrusore. Click per continuare."
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Misurare l'altezza di riferimento del punto di calibrazione"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " su 9"
|
||||
MSG_MEASURED_SKEW "Incl. misurata:"
|
||||
MSG_MENU_CALIBRATION "Calibrazione"
|
||||
MSG_MESH_BED_LEVELING "Mesh livel. letto"
|
||||
MSG_MOTION "Motion"
|
||||
MSG_MOVE_01MM "Move 0.1mm"
|
||||
MSG_MOVE_10MM "Move 10mm"
|
||||
MSG_MOVE_1MM "Move 1mm"
|
||||
MSG_MOVE_AXIS "Muovi asse"
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP "Calibrazione XYZ. Ruotare la manopola per alzare il carrello Z fino all'altezza massima. Click per terminare."
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Calibrazione Z. Ruotare la manopola per alzare il carrello Z fino all'altezza massima. Click per terminare."
|
||||
MSG_MOVE_E "Muovi Estrusore"
|
||||
MSG_MOVE_X "Muovi X"
|
||||
MSG_MOVE_Y "Muovi Y"
|
||||
MSG_MOVE_Z "Muovi Z"
|
||||
MSG_NEW_FIRMWARE_AVAILABLE "Nuova versione del firmware disponibile"
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Prega aggiorna."
|
||||
MSG_NO "No"
|
||||
MSG_NO_CARD "Nessuna SD"
|
||||
MSG_NO_MOVE "Nessun movimento."
|
||||
MSG_NOT_COLOR "Colore non puro"
|
||||
MSG_NOT_LOADED "Fil. non caricato"
|
||||
MSG_NOZZLE "Ugello"
|
||||
MSG_NOZZLE1 "Nozzle2"
|
||||
MSG_NOZZLE2 "Nozzle3"
|
||||
MSG_OK "ok"
|
||||
MSG_PAPER "Porre un foglio sotto l'ugello durante la calibrazione dei primi 4 punti. In caso l'ugello muova il foglio spegnere prontamente la stampante."
|
||||
MSG_PAUSE_PRINT "Metti in pausa"
|
||||
MSG_PICK_Z "Pick print"
|
||||
MSG_PID_EXTRUDER "Calibrazione PID"
|
||||
MSG_PID_FINISHED "Cal. PID completa"
|
||||
MSG_PID_RUNNING "Cal. PID"
|
||||
MSG_PINDA_NOT_CALIBRATED "Taratura della temperatura non ancora eseguita"
|
||||
MSG_PINDA_PREHEAT "Riscald. PINDA"
|
||||
MSG_PLA_FILAMENT_LOADED "Il PLA e stato caricato?"
|
||||
MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
MSG_PLEASE_LOAD_PLA "Per favore prima caricare filamento di PLA."
|
||||
MSG_PLEASE_WAIT "Aspetta"
|
||||
MSG_POSITION_UNKNOWN "Home X/Y before Z"
|
||||
MSG_POWERUP "PowerUp"
|
||||
MSG_PREHEAT "Preriscalda"
|
||||
MSG_PREHEAT_NOZZLE "Preris. ugello!"
|
||||
MSG_PREPARE_FILAMENT "Preparare filamento"
|
||||
MSG_PRESS "e cliccare manopola"
|
||||
MSG_PRINT_ABORTED "Stampa abortita"
|
||||
MSG_PRINT_PAUSED "Stampa in pausa"
|
||||
MSG_PRUSA3D "prusa3d.com"
|
||||
MSG_PRUSA3D_FORUM "forum.prusa3d.com"
|
||||
MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
|
||||
MSG_REBOOT "Riavvia stampante"
|
||||
MSG_REFRESH "\xF8" "Refresh"
|
||||
MSG_RESEND "Resend: "
|
||||
MSG_RESTORE_FAILSAFE "Restore failsafe"
|
||||
MSG_RESUME_PRINT "Riprendi stampa"
|
||||
MSG_RESUMING "Riprendi stampa"
|
||||
MSG_RESUMING_PRINT "Stampa in ripresa"
|
||||
MSG_RIGHT "Destra:"
|
||||
MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
MSG_SD_CARD_OK "SD card ok"
|
||||
MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
MSG_SD_FILE_OPENED "File opened: "
|
||||
MSG_SD_FILE_SELECTED "File selected"
|
||||
MSG_SD_INIT_FAIL "SD init fail"
|
||||
MSG_SD_INSERTED "SD inserita"
|
||||
MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
MSG_SD_REMOVED "SD rimossa"
|
||||
MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
MSG_SELFTEST "Autotest"
|
||||
MSG_SELFTEST_BEDHEATER "Letto/Riscald."
|
||||
MSG_SELFTEST_COOLING_FAN "Vent di stampa ant.?"
|
||||
MSG_SELFTEST_ENDSTOP "Finecorsa"
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT "Finec. fuori por."
|
||||
MSG_SELFTEST_ENDSTOPS "Finecorsa (2)"
|
||||
MSG_SELFTEST_ERROR "Autotest negativo"
|
||||
MSG_SELFTEST_EXTRUDER_FAN "Vent SX sull'ugello?"
|
||||
MSG_SELFTEST_FAILED "Autotest fallito"
|
||||
MSG_SELFTEST_FAN "Prova del ventilator"
|
||||
MSG_SELFTEST_FAN_NO "Non si gira"
|
||||
MSG_SELFTEST_FAN_YES "Gira"
|
||||
MSG_SELFTEST_HEATERTHERMISTOR "Riscald./Termist."
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT "Nessun errore"
|
||||
MSG_SELFTEST_CHECK_BED "Verifica letto"
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS "Verifica finecorsa"
|
||||
MSG_SELFTEST_CHECK_HOTEND "Verifica ugello"
|
||||
MSG_SELFTEST_CHECK_X "Verifica asse X"
|
||||
MSG_SELFTEST_CHECK_Y "Verifica asse Y"
|
||||
MSG_SELFTEST_CHECK_Z "Verifica asse Z"
|
||||
MSG_SELFTEST_MOTOR "Motore"
|
||||
MSG_SELFTEST_NOTCONNECTED "Non connesso"
|
||||
MSG_SELFTEST_OK "Autotest OK"
|
||||
MSG_SELFTEST_PLEASECHECK "Verificare:"
|
||||
MSG_SELFTEST_START "Avvia autotest"
|
||||
MSG_SELFTEST_WIRINGERROR "Errore cablaggio"
|
||||
MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
MSG_SET_HOME_OFFSETS "Set home offsets"
|
||||
MSG_SET_ORIGIN "Set origin"
|
||||
MSG_SET_TEMPERATURE "Imposta temperatura"
|
||||
MSG_SETTINGS "Impostazioni"
|
||||
MSG_SEVERE_SKEW "Inc. rilevante:"
|
||||
MSG_SHOW_END_STOPS "Stato finecorsa"
|
||||
MSG_SILENT_MODE_OFF "Mode [forte]"
|
||||
MSG_SILENT_MODE_ON "Modo [silenzioso]"
|
||||
MSG_SLIGHT_SKEW "Incl. leggera:"
|
||||
MSG_SPEED "Velocita"
|
||||
MSG_STATISTICS "Statistiche"
|
||||
MSG_STATS_FILAMENTUSED "Filamento usato:"
|
||||
MSG_STATS_PRINTTIME "Tempo di stampa:"
|
||||
MSG_STATS_TOTALFILAMENT "Filamento tot:"
|
||||
MSG_STATS_TOTALPRINTTIME "Tempo stampa tot:"
|
||||
MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
MSG_STOP_PRINT "Arresta stampa"
|
||||
MSG_STOPPED "ARRESTATO."
|
||||
MSG_STORE_EPROM "Store memory"
|
||||
MSG_SUPPORT "Support"
|
||||
MSG_SWITCH_PS_OFF "Switch power off"
|
||||
MSG_SWITCH_PS_ON "Switch power on"
|
||||
MSG_TAKE_EFFECT " per attualizzare"
|
||||
MSG_TEMP_CALIBRATION "Cal. temp. "
|
||||
MSG_TEMP_CALIBRATION_DONE "Taratura temperatura terminata. Fare click per continuare."
|
||||
MSG_TEMP_CALIBRATION_OFF "Cal. temp. [OFF]"
|
||||
MSG_TEMP_CALIBRATION_ON "Cal. temp. [ON]"
|
||||
MSG_TEMPERATURE "Temperatura"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
|
||||
MSG_TUNE "Regola"
|
||||
MSG_UNLOAD_ALL "Rilasciare tutti"
|
||||
MSG_UNLOAD_FILAMENT "Scarica filamento"
|
||||
MSG_UNLOAD_FILAMENT_1 "Rilasciare fil. 1"
|
||||
MSG_UNLOAD_FILAMENT_2 "Rilasciare fil. 1"
|
||||
MSG_UNLOAD_FILAMENT_3 "Rilasciare fil. 1"
|
||||
MSG_UNLOAD_FILAMENT_4 "Rilasciare fil. 1"
|
||||
MSG_UNLOADING_FILAMENT "Rilasc. filamento"
|
||||
MSG_USB_PRINTING "Stampa da USB"
|
||||
MSG_USED "Usati nella stampa"
|
||||
MSG_USERWAIT "Attendendo utente"
|
||||
MSG_V2_CALIBRATION "Cal. primo layer."
|
||||
MSG_VOLUMETRIC "Filament"
|
||||
MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
MSG_WAITING_TEMP "In attesa del raffreddamento della testina e del piatto"
|
||||
MSG_WATCH "Schermata info"
|
||||
MSG_WIZARD "Wizard"
|
||||
MSG_WIZARD_CALIBRATION_FAILED "Per favore consulta il nostro manuale per risolvere il problema. Poi riprendi il Wizard dopo aver riavviato la stampante."
|
||||
MSG_WIZARD_CLEAN_HEATBED "Per favore pulisci il piatto, poi premi la manopola."
|
||||
MSG_WIZARD_DONE "Ben fatto. Buona stampa!"
|
||||
MSG_WIZARD_FILAMENT_LOADED "Il filamento e stato caricato?"
|
||||
MSG_WIZARD_HEATING "Sto preriscaldando l'ugello. Per favore attendi."
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT "Per favore carica filamento di PLA e riprendi il Wizard dopo aver riavviato la stampante."
|
||||
MSG_WIZARD_LOAD_FILAMENT "Per favore inserisci il filamento di PLA nell'estrusore, poi premi la manopola per caricare."
|
||||
MSG_WIZARD_PLA_FILAMENT "E questo un filamento di PLA?"
|
||||
MSG_WIZARD_QUIT "E possibile proseguire la guide Wizard in qualsiasi momento attraverso Calibrazione -> Wizard."
|
||||
MSG_WIZARD_REPEAT_V2_CAL "Desideri ripetere l'ultimo passaggio per migliorare la distanza fra ugello e piatto?"
|
||||
MSG_WIZARD_RERUN "Se avvi il Wizard perderai la calibrazione preesistente e dovrai ricominciare dall'inizio. Continuare?"
|
||||
MSG_WIZARD_SELFTEST "Anzitutto avviero il Self Test per controllare gli errori di assemblaggio piu comuni."
|
||||
MSG_WIZARD_V2_CAL "Adesso tarero lo stacco fra ugello e superfice del piatto."
|
||||
MSG_WIZARD_V2_CAL_2 "Adesso iniziero a stampare una linea e tu dovrai abbassare l'ugello poco per volta ruotando la manopola sino a raggiungere una altezza ottimale. Per favore dai uno sguardo all'immagine del nostro manuale, cap.Calibrazione."
|
||||
MSG_WIZARD_WELCOME "Ciao, sono la tua stampante Original Prusa i3. Gradiresti aiuto attraverso il processo di configurazione?"
|
||||
MSG_WIZARD_WILL_PREHEAT "Adesso preriscaldero l'ugello per PLA."
|
||||
MSG_WIZARD_XYZ_CAL "Adesso avviero una Calibrazione XYZ. Puo durare circa 12 min."
|
||||
MSG_WIZARD_Z_CAL "Adesso avviero una Calibrazione Z."
|
||||
MSG_XYZ_DETAILS "XYZ Cal. dettagli"
|
||||
MSG_Y_DISTANCE_FROM_MIN "Distanza Y da min:"
|
||||
MSG_YES "Si"
|
||||
MSG_ZPROBE_OUT "Z probe out. bed"
|
||||
MSG_ZPROBE_ZOFFSET "Z Offset"
|
||||
WELCOME_MSG CUSTOM_MENDEL_NAME " pronta."
|
295
lang_upgrade/msgs_pl.txt
Normal file
295
lang_upgrade/msgs_pl.txt
Normal file
@ -0,0 +1,295 @@
|
||||
MSG_ADJUSTZ "Autodostroic Z?"
|
||||
MSG_ALL "Wszystko"
|
||||
MSG_AUTO_HOME "Auto home"
|
||||
MSG_BABYSTEP_X "Babystep X"
|
||||
MSG_BABYSTEP_Y "Babystep Y"
|
||||
MSG_BABYSTEP_Z "Dostrojenie osy Z"
|
||||
MSG_BABYSTEP_Z_NOT_SET "Odleglosc dyszy od podkladki nie jest skalibrowana. Postepuj zgodnie z instrukcja rozdzial Zaczynamy, podrozdzial Kalibracja pierwszej warstwy."
|
||||
MSG_BABYSTEPPING_X "Babystepping X"
|
||||
MSG_BABYSTEPPING_Y "Babystepping Y"
|
||||
MSG_BABYSTEPPING_Z "Dostrojenie Z"
|
||||
MSG_BED "Stolik"
|
||||
MSG_BED_CORRECTION_FRONT "Do przodu [um]"
|
||||
MSG_BED_CORRECTION_LEFT "W lewo [um]"
|
||||
MSG_BED_CORRECTION_MENU "Korekta podkladki"
|
||||
MSG_BED_CORRECTION_REAR "Do tylu [um]"
|
||||
MSG_BED_CORRECTION_RESET "Reset"
|
||||
MSG_BED_CORRECTION_RIGHT "W prawo [um]"
|
||||
MSG_BED_DONE "Stolik OK."
|
||||
MSG_BED_HEATING "Grzanie stolika.."
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH "Kalibracja Z nieudana. Sensor dotk. za wysoko. Czekam na reset."
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW "Kalibracja nieudana. Sensor nie dotknal. Zanieczysz. dysza? Czekam na reset."
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Kalibracja nieudana. Sensor odlaczony lub uszkodz. kabel. Czekam na reset."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "Kalibr. XYZ nieudana. Przed. punkty kalibr. zbyt do przodu. Wyrownac drukarke."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "Kalibr. XYZ nieudana. Lewy przedni punkt zbyt do przodu. Wyrownac drukarke."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "Kalibr. XYZ nieudana. Prawy przedni punkt zbyt do przodu. Wyrownac drukarke."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Kalibracja XYZ niepowiedziona. Sprawdzic w instrukcji."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Kalibracja XYZ ok. Osie X/Y sa prostopadle. Gratulacje!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Kalibr. XYZ nieudana. Kalibracyjny punkt podkladki nieznaleziony."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "Kalibracja XYZ prawidlowa. Skosy beda automatycznie wyrownane przy druku."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "Kalibracja XYZ prawidlowa. Osie X/Y lekko skosne. Dobra robota!"
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "Kalibr. XYZ niedokladna. Przednie punkty kalibr. Zbyt wys. do przodu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "Kalibracja XYZ niedokladna. Lewy przedni punkt zbyt wysuniety do przodu."
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "Kalibracja XYZ niedokladna. Prawy przedni punkt zbyt wysuniety do przodu."
|
||||
MSG_BEGIN_FILE_LIST "Begin file list"
|
||||
MSG_CALIBRATE_BED "Kalibracja XYZ"
|
||||
MSG_CALIBRATE_BED_RESET "Reset kalibr. XYZ"
|
||||
MSG_CALIBRATE_E "Kalibruj E"
|
||||
MSG_CALIBRATE_PINDA "Skalibrowac"
|
||||
MSG_CALIBRATION_PINDA_MENU "Cieplna kalibr."
|
||||
MSG_CARD_MENU "Druk z SD"
|
||||
MSG_CLEAN_NOZZLE_E "Kalibracja E skonczona. Prosze oczyscic dysze. Potem potwierdzic przyciskiem. "
|
||||
MSG_CNG_SDCARD "Vymenit SD"
|
||||
MSG_CONFIGURATION_VER " Last Updated: "
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Oba wozki dojechaly do gornej ramy?"
|
||||
MSG_CONFIRM_NOZZLE_CLEAN "Dla prawidl. kalibracji prosze oczyscic dysze. Potw. guzikiem."
|
||||
MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Dla prawidlowej kalibracji prosze oczyscic dysze. Potem potwierdzic przyciskiem."
|
||||
MSG_CONTROL "Kontrola"
|
||||
MSG_COOLDOWN "Wychlodzic"
|
||||
MSG_CORRECTLY "Wymiana ok?"
|
||||
MSG_CURRENT "Tylko aktualne"
|
||||
MSG_DATE "Data:"
|
||||
MSG_DISABLE_STEPPERS "Wylaczyc silniki"
|
||||
MSG_DWELL "Sleep..."
|
||||
MSG_E_CAL_KNOB "Prosze otaczac przycisk poki znacznik nie dosiegnie ciala ekstrudera. Potwierdzic przyciskiem."
|
||||
MSG_END_FILE_LIST "End file list"
|
||||
MSG_ENDSTOP_HIT "TRIGGERED"
|
||||
MSG_ENDSTOP_OPEN "open"
|
||||
MSG_ENDSTOPS_HIT "endstops hit: "
|
||||
MSG_Enqueing "enqueing \""
|
||||
MSG_ERR_COLD_EXTRUDE_STOP " cold extrusion prevented"
|
||||
MSG_ERR_CHECKSUM_MISMATCH "checksum mismatch, Last Line: "
|
||||
MSG_ERR_KILLED "Printer halted. kill() called!"
|
||||
MSG_ERR_NO_CHECKSUM "No Checksum with line number, Last Line: "
|
||||
MSG_ERR_NO_THERMISTORS "No thermistors - no temperature"
|
||||
MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
|
||||
MSG_ERROR "BLAD:"
|
||||
MSG_EXTRUDER "Ekstruder"
|
||||
MSG_EXTRUDER_1 "Ekstruder 1"
|
||||
MSG_EXTRUDER_2 "Ekstruder 2"
|
||||
MSG_EXTRUDER_3 "Ekstruder 3"
|
||||
MSG_EXTRUDER_4 "Ekstruder 4"
|
||||
MSG_FACTOR " \002 Fact"
|
||||
MSG_FAN_SPEED "Predkosc went."
|
||||
MSG_FIL_ADJUSTING "Przebiega wyrownanie filamentow. Prosze czekac."
|
||||
MSG_FILAMENT_CLEAN "Czy kolor jest czysty?"
|
||||
MSG_FILAMENT_LOADING_T0 "Wloz filament do ekstrudera 1. Potwierdz przyciskiem."
|
||||
MSG_FILAMENT_LOADING_T1 "Wloz filament do ekstrudera 2. Potwierdz przyciskiem."
|
||||
MSG_FILAMENT_LOADING_T2 "Wloz filament do ekstrudera 3. Potwierdz przyciskiem."
|
||||
MSG_FILAMENT_LOADING_T3 "Wloz filament do ekstrudera 4. Potwierdz przyciskiem."
|
||||
MSG_FILAMENTCHANGE "Wymienic filament"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteracja "
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Szukam punktu kalibracyjnego podkladki"
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
MSG_FINISHING_MOVEMENTS "Konczenie druku"
|
||||
MSG_FLOW "Przeplyw"
|
||||
MSG_FLOW0 "Prutok 0"
|
||||
MSG_FLOW1 "Prutok 1"
|
||||
MSG_FLOW2 "Prutok 2"
|
||||
MSG_FOLLOW_CALIBRATION_FLOW "Drukarka nie zostala jeszcze skalibrowana. Prosze kierowac sie instrukcja, rozdzial Zaczynamy, podrozdzial Selftest."
|
||||
MSG_FREE_MEMORY " Free Memory: "
|
||||
MSG_HEATING "Grzanie..."
|
||||
MSG_HEATING_COMPLETE "Grzanie OK."
|
||||
MSG_HOMEYZ "Kalibruj Z"
|
||||
MSG_HOMEYZ_DONE "Kalibracja OK"
|
||||
MSG_HOMEYZ_PROGRESS "Kalibruje Z"
|
||||
MSG_CHANGE_EXTR "Zmienic ekstruder"
|
||||
MSG_CHANGE_SUCCESS "Wymiana ok!"
|
||||
MSG_CHANGING_FILAMENT "Wymiana filamentu"
|
||||
MSG_CHOOSE_EXTRUDER "Wybierz ekstruder"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Poprawiam precyzyjnosc punktu kalibracyjnego"
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " z 4"
|
||||
MSG_INIT_SDCARD "Inic. SD"
|
||||
MSG_INSERT_FILAMENT "Wprowadz filament"
|
||||
MSG_KILLED "KILLED. "
|
||||
MSG_LANGUAGE_NAME "Polski"
|
||||
MSG_LANGUAGE_SELECT "Wybor jezyka"
|
||||
MSG_LEFT "Lewy:"
|
||||
MSG_LOAD_ALL "Zalad. wszystkie"
|
||||
MSG_LOAD_EPROM "Ulozit pamet"
|
||||
MSG_LOAD_FILAMENT "Wprowadz filament"
|
||||
MSG_LOAD_FILAMENT_1 "Zaladowac fil. 1"
|
||||
MSG_LOAD_FILAMENT_2 "Zaladowac fil. 2"
|
||||
MSG_LOAD_FILAMENT_3 "Zaladowac fil. 3"
|
||||
MSG_LOAD_FILAMENT_4 "Zaladowac fil. 4"
|
||||
MSG_LOADING_COLOR "Czyszcz. koloru"
|
||||
MSG_LOADING_FILAMENT "Wprow. filamentu"
|
||||
MSG_LOOSE_PULLEY "Kolo pasowe"
|
||||
MSG_M104_INVALID_EXTRUDER "M104 Invalid extruder "
|
||||
MSG_M105_INVALID_EXTRUDER "M105 Invalid extruder "
|
||||
MSG_M109_INVALID_EXTRUDER "M109 Invalid extruder "
|
||||
MSG_M117_V2_CALIBRATION "M117 Kal. 1. warstwy"
|
||||
MSG_M119_REPORT "Reporting endstop status"
|
||||
MSG_M200_INVALID_EXTRUDER "M200 Invalid extruder "
|
||||
MSG_M218_INVALID_EXTRUDER "M218 Invalid extruder "
|
||||
MSG_M221_INVALID_EXTRUDER "M221 Invalid extruder "
|
||||
MSG_MAIN "Menu glowne"
|
||||
MSG_MARK_FIL "Prosze oznaczyc filament 100 mm od ciala ekstrudera. Potwierdzic przyciskiem."
|
||||
MSG_MAX " \002 Max"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Okreslam wysokosc odniesienia punktu kalibracyjnego"
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " z 9"
|
||||
MSG_MEASURED_SKEW "Zmier. sciecie:"
|
||||
MSG_MENU_CALIBRATION "Kalibracja"
|
||||
MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
|
||||
MSG_MIN " \002 Min"
|
||||
MSG_MOVE_AXIS "Ruch osi"
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP "Kalibracja XYZ. Przekrec galke, aby przesunac os Z do gornych krancowek. Nacisnij, by potwierdzic."
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Kalibracja Z. Przekrec galke, aby przesunac os Z do gornych krancowek. Nacisnij, by potwierdzic."
|
||||
MSG_MOVE_E "Extruder"
|
||||
MSG_MOVE_X "Przesunac X"
|
||||
MSG_MOVE_Y "Przesunac Y"
|
||||
MSG_MOVE_Z "Przesunac Z"
|
||||
MSG_NEW_FIRMWARE_AVAILABLE "Wyszla nowa wersja firmware:"
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Prosze zaktualizowac"
|
||||
MSG_NO "Nie"
|
||||
MSG_NO_CARD "Brak karty SD"
|
||||
MSG_NO_MOVE "No move."
|
||||
MSG_NOT_COLOR "Kolor zanieczysz."
|
||||
MSG_NOT_LOADED "Brak filamentu"
|
||||
MSG_NOZZLE "Dysza"
|
||||
MSG_NOZZLE1 "Tryska2"
|
||||
MSG_NOZZLE2 "Tryska3"
|
||||
MSG_OK "ok"
|
||||
MSG_PAPER "Umiesc kartke papieru na podkladce i trzymaj pod dysza podczas pomiaru pierwszych 4 punktow. Jesli dysza zahaczy o papier, wylacz drukarke."
|
||||
MSG_PAUSE_PRINT "Przerwac druk"
|
||||
MSG_PICK_Z "Vyberte vytisk"
|
||||
MSG_PID_EXTRUDER "Kalibracja PID"
|
||||
MSG_PID_FINISHED "Kal. PID zakonczona"
|
||||
MSG_PID_RUNNING "Kal. PID"
|
||||
MSG_PINDA_NOT_CALIBRATED "Cieplna kalibracja nie byla przeprowadzona"
|
||||
MSG_PINDA_PREHEAT "Grzanie PINDA"
|
||||
MSG_PLA_FILAMENT_LOADED "Fialment PLA jest zaladowany?"
|
||||
MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
|
||||
MSG_PLEASE_LOAD_PLA "Prosze, najpierw zaladuj filament PLA."
|
||||
MSG_PLEASE_WAIT "Prosze czekac"
|
||||
MSG_POWERUP "PowerUp"
|
||||
MSG_PREHEAT "Grzanie"
|
||||
MSG_PREHEAT_NOZZLE "Nagrzej dysze!"
|
||||
MSG_PREPARE_FILAMENT "Przygotuj filament"
|
||||
MSG_PREPARE_FILAMENT "Przygotuj filament"
|
||||
MSG_PRESS "Nacisnij przycisk"
|
||||
MSG_PRINT_ABORTED "Druk przerwany"
|
||||
MSG_PRINT_PAUSED "Druk zatrzymany"
|
||||
MSG_PRUSA3D "prusa3d.cz"
|
||||
MSG_PRUSA3D_FORUM "forum.prusa3d.cz"
|
||||
MSG_PRUSA3D_HOWTO "howto.prusa3d.cz"
|
||||
MSG_REBOOT "Restart drukarki"
|
||||
MSG_REFRESH "\xF8" "Obnovit"
|
||||
MSG_RESEND "Resend: "
|
||||
MSG_RESTORE_FAILSAFE "Obnovit vychozi"
|
||||
MSG_RESUME_PRINT "Kontynuowac"
|
||||
MSG_RESUMING "Wznowienie druku"
|
||||
MSG_RESUMING_PRINT "Wznawianie druku"
|
||||
MSG_RIGHT "Prawy:"
|
||||
MSG_SD_CANT_ENTER_SUBDIR "Cannot enter subdir: "
|
||||
MSG_SD_CANT_OPEN_SUBDIR "Cannot open subdir"
|
||||
MSG_SD_CARD_OK "SD card ok"
|
||||
MSG_SD_ERR_WRITE_TO_FILE "error writing to file"
|
||||
MSG_SD_FILE_OPENED "File opened: "
|
||||
MSG_SD_FILE_SELECTED "File selected"
|
||||
MSG_SD_INIT_FAIL "SD init fail"
|
||||
MSG_SD_INSERTED "Karta wlozona"
|
||||
MSG_SD_NOT_PRINTING "Not SD printing"
|
||||
MSG_SD_OPEN_FILE_FAIL "open failed, File: "
|
||||
MSG_SD_OPENROOT_FAIL "openRoot failed"
|
||||
MSG_SD_PRINTING_BYTE "SD printing byte "
|
||||
MSG_SD_REMOVED "Karta wyjeta"
|
||||
MSG_SD_VOL_INIT_FAIL "volume.init failed"
|
||||
MSG_SD_WORKDIR_FAIL "workDir open failed"
|
||||
MSG_SD_WRITE_TO_FILE "Writing to file: "
|
||||
MSG_SELFTEST "Selftest "
|
||||
MSG_SELFTEST_BEDHEATER "Bed / Heater"
|
||||
MSG_SELFTEST_COOLING_FAN "Przedni went. druku?"
|
||||
MSG_SELFTEST_ENDSTOP "Endstop"
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
|
||||
MSG_SELFTEST_ENDSTOPS "Endstops"
|
||||
MSG_SELFTEST_ERROR "Selftest error !"
|
||||
MSG_SELFTEST_EXTRUDER_FAN "Lewy went na dysze?"
|
||||
MSG_SELFTEST_FAILED "Selftest nieudany"
|
||||
MSG_SELFTEST_FAN "Test wentylatora"
|
||||
MSG_SELFTEST_FAN_NO "Nie kreci sie"
|
||||
MSG_SELFTEST_FAN_YES "Kreci sie"
|
||||
MSG_SELFTEST_HEATERTHERMISTOR "Heater/Thermistor"
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT "Wszystko OK "
|
||||
MSG_SELFTEST_CHECK_BED "Kontrola bed "
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS "Kontrola endstops"
|
||||
MSG_SELFTEST_CHECK_HOTEND "Kontrola hotend "
|
||||
MSG_SELFTEST_CHECK_X "Kontrola X axis "
|
||||
MSG_SELFTEST_CHECK_Y "Kontrola Y axis "
|
||||
MSG_SELFTEST_CHECK_Z "Kontrola Z axis "
|
||||
MSG_SELFTEST_MOTOR "Silnik"
|
||||
MSG_SELFTEST_NOTCONNECTED "Nie podlaczono "
|
||||
MSG_SELFTEST_OK "Self test OK"
|
||||
MSG_SELFTEST_PLEASECHECK "Skontroluj :"
|
||||
MSG_SELFTEST_START "Self test start "
|
||||
MSG_SELFTEST_WIRINGERROR "Blad polaczenia"
|
||||
MSG_SERIAL_ERROR_MENU_STRUCTURE "Error in menu structure"
|
||||
MSG_SET_HOME_OFFSETS "Nastav pocatek home"
|
||||
MSG_SET_ORIGIN "Nastav pocatek"
|
||||
MSG_SET_TEMPERATURE "Ustawic temperature"
|
||||
MSG_SETTINGS "Ustawienia"
|
||||
MSG_SEVERE_SKEW "Ostre sciecie:"
|
||||
MSG_SHOW_END_STOPS "Pokaz krancowki"
|
||||
MSG_SILENT_MODE_OFF "Tryb[w wydajnosc]"
|
||||
MSG_SILENT_MODE_ON "Tryb [cichy]"
|
||||
MSG_SLIGHT_SKEW "Lekkie sciecie:"
|
||||
MSG_SPEED "Predkosc"
|
||||
MSG_STATISTICS "Statystyka "
|
||||
MSG_STATS_FILAMENTUSED "Filament : "
|
||||
MSG_STATS_PRINTTIME "Czas druku : "
|
||||
MSG_STATS_TOTALFILAMENT "Filament lacznie :"
|
||||
MSG_STATS_TOTALPRINTTIME "Czas calkowity :"
|
||||
MSG_STEPPER_TOO_HIGH "Steprate too high: "
|
||||
MSG_STOP_PRINT "Zatrzymac druk"
|
||||
MSG_STOPPED "STOPPED. "
|
||||
MSG_STORE_EPROM "Store memory"
|
||||
MSG_SUPPORT "Pomoc"
|
||||
MSG_SWITCH_PS_OFF "Zapnout zdroj"
|
||||
MSG_SWITCH_PS_ON "Vypnout zdroj"
|
||||
MSG_TAKE_EFFECT " wprow. zmian"
|
||||
MSG_TEMP_CALIBRATION "Ciepl. kal. "
|
||||
MSG_TEMP_CALIBRATION_DONE "Cieplna kalibracja zakonczona. Kontynuuj przyciskiem"
|
||||
MSG_TEMP_CALIBRATION_OFF "Ciepl. kal. [OFF]"
|
||||
MSG_TEMP_CALIBRATION_ON "Ciepl. kal. [ON]"
|
||||
MSG_TEMPERATURE "Temperatura"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "karta SD [normal]"
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "karta SD[FlshAir]"
|
||||
MSG_TUNE "Nastroic"
|
||||
MSG_UNLOAD_ALL "Wyjac wszystkie"
|
||||
MSG_UNLOAD_FILAMENT "Wyjac filament"
|
||||
MSG_UNLOAD_FILAMENT_1 "Wyjac filament 1"
|
||||
MSG_UNLOAD_FILAMENT_2 "Wyjac filament 2"
|
||||
MSG_UNLOAD_FILAMENT_3 "Wyjac filament 3"
|
||||
MSG_UNLOAD_FILAMENT_4 "Wyjac filament 4"
|
||||
MSG_UNLOADING_FILAMENT "Wysuwam filament"
|
||||
MSG_USB_PRINTING "Druk z USB "
|
||||
MSG_USED "Uzyte przy druku"
|
||||
MSG_USERWAIT "Wait for user..."
|
||||
MSG_V2_CALIBRATION "Kal. 1. warstwy"
|
||||
MSG_VOLUMETRIC "Filament"
|
||||
MSG_VOLUMETRIC_ENABLED "E in mm3"
|
||||
MSG_WAITING_TEMP "Oczekiwanie na wychlodzenie dyszy i podkladki."
|
||||
MSG_WATCH "Informacje"
|
||||
MSG_WIZARD "Wizard"
|
||||
MSG_WIZARD_CALIBRATION_FAILED "Prosze sprawdz nasz poradnik i napraw problem. Potem przywroc Wizard restartujac drukarke."
|
||||
MSG_WIZARD_CLEAN_HEATBED "Prosze oczysc stolik i nacisnij guzik."
|
||||
MSG_WIZARD_DONE "Gotowe. Udanego druku!"
|
||||
MSG_WIZARD_FILAMENT_LOADED "Filament jest zaladowany?"
|
||||
MSG_WIZARD_HEATING "Nagrzewanie dyszy. Prosze czekac."
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT "Prosze zaladuj filament PLA i przywroc Wizard przez restart drukarki."
|
||||
MSG_WIZARD_LOAD_FILAMENT "Prosze umiesc filament PLA w ekstruderze i nacisnij przycisk by zaladowac."
|
||||
MSG_WIZARD_PLA_FILAMENT "Czy to filament PLA?"
|
||||
MSG_WIZARD_QUIT "Zawsze mozesz przywrocic Wizard przez Kalibracja -> Wizard."
|
||||
MSG_WIZARD_REPEAT_V2_CAL "Chcesz powtorzyc ostatni krok i przestawic odleglosc miedzy dysza a stolikiem?"
|
||||
MSG_WIZARD_RERUN "Wlaczenie Wizard usunie obecne dane kalibracyjne i zacznie od nowa. Kontynuowac?"
|
||||
MSG_WIZARD_SELFTEST "Najpierw wlacze autotest w celu kontrolli najczestszych problemow z montazem."
|
||||
MSG_WIZARD_V2_CAL "Kalibruje odleglosc miedzy koncowka dyszy a stolikiem."
|
||||
MSG_WIZARD_V2_CAL_2 "Zaczne drukowac linie. Stopniowo opuszczaj dysze przekrecajac guzik, poki nie uzyskasz optymalnej wysokosci. Sprawdz obrazki w naszym poradniku w rozdz. Kalibracja"
|
||||
MSG_WIZARD_WELCOME "Czesc, jestem Twoja drukarka Original Prusa i3. Czy potrzebujesz pomocy z instalacja?"
|
||||
MSG_WIZARD_WILL_PREHEAT "Nagrzewam dysze dla PLA."
|
||||
MSG_WIZARD_XYZ_CAL "Wlaczam kalibracje xyz. Zajmie to ok. 12 min."
|
||||
MSG_WIZARD_Z_CAL "Wlaczam kalibracje z."
|
||||
MSG_XYZ_DETAILS "Szczegoly kal.XYZ"
|
||||
MSG_Y_DISTANCE_FROM_MIN "Odleglosc Y od min.:"
|
||||
MSG_YES "Tak"
|
||||
WELCOME_MSG CUSTOM_MENDEL_NAME " gotowa"
|
399
lang_upgrade/msgs_usage.txt
Normal file
399
lang_upgrade/msgs_usage.txt
Normal file
@ -0,0 +1,399 @@
|
||||
MSG_BABYSTEP_X 0
|
||||
MSG_BABYSTEP_Y 0
|
||||
MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ 0
|
||||
MSG_CONTROL 0
|
||||
MSG_CRASH_DETECTED2 0
|
||||
MSG_FIL_ADJUSTING 0
|
||||
MSG_FLOW0 0
|
||||
MSG_FLOW1 0
|
||||
MSG_FLOW2 0
|
||||
MSG_FW_VERSION_RC 0
|
||||
MSG_INFO_FILAMENT_XDIFF 0
|
||||
MSG_INFO_FILAMENT_YDIFF 0
|
||||
MSG_LANGUAGE_NAME 0
|
||||
MSG_LOAD_EPROM 0
|
||||
MSG_MOTION 0
|
||||
MSG_REBOOT 0
|
||||
MSG_RECTRACT 0
|
||||
MSG_RESTORE_FAILSAFE 0
|
||||
MSG_SD_NOT_PRINTING 0
|
||||
MSG_SERIAL_ERROR_MENU_STRUCTURE 0
|
||||
MSG_SET_HOME_OFFSETS 0
|
||||
MSG_SET_ORIGIN 0
|
||||
MSG_STEPPER_TIMER_OVERFLOW_ERROR 0
|
||||
MSG_STORE_EPROM 0
|
||||
MSG_SWITCH_PS_OFF 0
|
||||
MSG_SWITCH_PS_ON 0
|
||||
MSG_TAKE_EFFECT 0
|
||||
MSG_USB_PRINTING 0
|
||||
MSG_VOLUMETRIC 0
|
||||
MSG_VOLUMETRIC_ENABLED 0
|
||||
MSG_ACTIVE_EXTRUDER 1
|
||||
MSG_ADJUSTZ 1
|
||||
MSG_AUTHOR 1
|
||||
MSG_AUTOLOAD_FILAMENT 1
|
||||
MSG_AUTOLOADING_ENABLED 1
|
||||
MSG_AUTOLOADING_ONLY_IF_FSENS_ON 1
|
||||
MSG_BABYSTEPPING_X 1
|
||||
MSG_BABYSTEPPING_Y 1
|
||||
MSG_BABYSTEPPING_Z 1
|
||||
MSG_BED_CORRECTION_FRONT 1
|
||||
MSG_BED_CORRECTION_LEFT 1
|
||||
MSG_BED_CORRECTION_MENU 1
|
||||
MSG_BED_CORRECTION_REAR 1
|
||||
MSG_BED_CORRECTION_RESET 1
|
||||
MSG_BED_CORRECTION_RIGHT 1
|
||||
MSG_BED_HEATING_SAFETY_DISABLED 1
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH 1
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR 1
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR 1
|
||||
MSG_BEGIN_FILE_LIST 1
|
||||
MSG_CALIBRATE_BED 1
|
||||
MSG_CALIBRATE_BED_RESET 1
|
||||
MSG_CALIBRATE_E 1
|
||||
MSG_CALIBRATE_PINDA 1
|
||||
MSG_CALIBRATION_PINDA_MENU 1
|
||||
MSG_CLEAN_NOZZLE_E 1
|
||||
MSG_CNG_SDCARD 1
|
||||
MSG_CONFIGURATION_VER 1
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP 1
|
||||
MSG_CORRECTLY 1
|
||||
MSG_COUNT_X 1
|
||||
MSG_CRASH_DET_ONLY_IN_NORMAL 1
|
||||
MSG_CRASH_DET_STEALTH_FORCE_OFF 1
|
||||
MSG_CURRENT 1
|
||||
MSG_DATE 1
|
||||
MSG_DEFAULT_SETTINGS_LOADED 1
|
||||
MSG_DISABLE_STEPPERS 1
|
||||
MSG_DWELL 1
|
||||
MSG_E_CAL_KNOB 1
|
||||
MSG_END_FILE_LIST 1
|
||||
MSG_ERR_COLD_EXTRUDE_STOP 1
|
||||
MSG_ERR_CHECKSUM_MISMATCH 1
|
||||
MSG_ERR_KILLED 1
|
||||
MSG_ERR_LINE_NO 1
|
||||
MSG_ERR_LONG_EXTRUDE_STOP 1
|
||||
MSG_ERR_NO_CHECKSUM 1
|
||||
MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM 1
|
||||
MSG_ERR_NO_THERMISTORS 1
|
||||
MSG_EXTRUDER_1 1
|
||||
MSG_EXTRUDER_2 1
|
||||
MSG_EXTRUDER_3 1
|
||||
MSG_EXTRUDER_4 1
|
||||
MSG_EXTRUDER_CORRECTION 1
|
||||
MSG_EXTRUDER_CORRECTION_OFF 1
|
||||
MSG_FACTOR 1
|
||||
MSG_FANS_CHECK_OFF 1
|
||||
MSG_FANS_CHECK_ON 1
|
||||
MSG_FILAMENT_SENSOR 1
|
||||
MSG_FILE_CNT 1
|
||||
MSG_FILE_INCOMPLETE 1
|
||||
MSG_FILE_PRINTED 1
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION 1
|
||||
MSG_FLOW 1
|
||||
MSG_FORCE_SELFTEST 1
|
||||
MSG_FREE_MEMORY 1
|
||||
MSG_FSENS_AUTOLOAD_OFF 1
|
||||
MSG_FSENS_AUTOLOAD_ON 1
|
||||
MSG_FSENS_NOT_RESPONDING 1
|
||||
MSG_FSENSOR_NA 1
|
||||
MSG_FW_VERSION_ALPHA 1
|
||||
MSG_FW_VERSION_BETA 1
|
||||
MSG_FW_VERSION_UNKNOWN 1
|
||||
MSG_HOMEYZ_DONE 1
|
||||
MSG_HOMEYZ_PROGRESS 1
|
||||
MSG_CHANGE_EXTR 1
|
||||
MSG_CHANGE_SUCCESS 1
|
||||
MSG_CHANGED_BOTH 1
|
||||
MSG_CHANGED_MOTHERBOARD 1
|
||||
MSG_CHANGED_PRINTER 1
|
||||
MSG_CHANGING_FILAMENT 1
|
||||
MSG_CHECK_IDLER 1
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 1
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 1
|
||||
MSG_INFO_EXTRUDER 1
|
||||
MSG_INFO_NOZZLE_FAN 1
|
||||
MSG_INFO_PRINT_FAN 1
|
||||
MSG_INIT_SDCARD 1
|
||||
MSG_INSERT_FILAMENT 1
|
||||
MSG_INVALID_EXTRUDER 1
|
||||
MSG_KILLED 1
|
||||
MSG_LANGUAGE_SELECT 1
|
||||
MSG_LEFT 1
|
||||
MSG_LOAD_ALL 1
|
||||
MSG_LOAD_FILAMENT_1 1
|
||||
MSG_LOAD_FILAMENT_2 1
|
||||
MSG_LOAD_FILAMENT_3 1
|
||||
MSG_LOAD_FILAMENT_4 1
|
||||
MSG_LOADING_COLOR 1
|
||||
MSG_LOOSE_PULLEY 1
|
||||
MSG_M104_INVALID_EXTRUDER 1
|
||||
MSG_M105_INVALID_EXTRUDER 1
|
||||
MSG_M109_INVALID_EXTRUDER 1
|
||||
MSG_M119_REPORT 1
|
||||
MSG_M200_INVALID_EXTRUDER 1
|
||||
MSG_M218_INVALID_EXTRUDER 1
|
||||
MSG_M221_INVALID_EXTRUDER 1
|
||||
MSG_MARK_FIL 1
|
||||
MSG_MAX 1
|
||||
MSG_MEASURED_OFFSET 1
|
||||
MSG_MEASURED_SKEW 1
|
||||
MSG_MENU_BELT_STATUS 1
|
||||
MSG_MENU_TEMPERATURES 1
|
||||
MSG_MENU_VOLTAGES 1
|
||||
MSG_MESH_BED_LEVELING 1
|
||||
MSG_MIN 1
|
||||
MSG_MOVE_AXIS 1
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP 1
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z 1
|
||||
MSG_MOVE_E 1
|
||||
MSG_MOVE_X 1
|
||||
MSG_MOVE_Y 1
|
||||
MSG_MOVE_Z 1
|
||||
MSG_NEW_FIRMWARE_AVAILABLE 1
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE 1
|
||||
MSG_NO_CARD 1
|
||||
MSG_NO_MOVE 1
|
||||
MSG_NOT_COLOR 1
|
||||
MSG_NOT_LOADED 1
|
||||
MSG_NOZZLE1 1
|
||||
MSG_NOZZLE2 1
|
||||
MSG_PAUSE_PRINT 1
|
||||
MSG_PICK_Z 1
|
||||
MSG_PID_EXTRUDER 1
|
||||
MSG_PID_FINISHED 1
|
||||
MSG_PID_RUNNING 1
|
||||
MSG_PINDA_NOT_CALIBRATED 1
|
||||
MSG_PINDA_PREHEAT 1
|
||||
MSG_PLA_FILAMENT_LOADED 1
|
||||
MSG_PLANNER_BUFFER_BYTES 1
|
||||
MSG_PLEASE_LOAD_PLA 1
|
||||
MSG_PREHEAT 1
|
||||
MSG_PREPARE_FILAMENT 1
|
||||
MSG_PRESS 1
|
||||
MSG_PRESS_TO_PREHEAT 1
|
||||
MSG_PRINT_PAUSED 1
|
||||
MSG_PRINTER_DISCONNECTED 1
|
||||
MSG_PRUSA3D 1
|
||||
MSG_PRUSA3D_FORUM 1
|
||||
MSG_PRUSA3D_HOWTO 1
|
||||
MSG_RECOVERING_PRINT 1
|
||||
MSG_RESEND 1
|
||||
MSG_RESUME_PRINT 1
|
||||
MSG_RESUMING 1
|
||||
MSG_RESUMING_PRINT 1
|
||||
MSG_RIGHT 1
|
||||
MSG_SD_CANT_ENTER_SUBDIR 1
|
||||
MSG_SD_CANT_OPEN_SUBDIR 1
|
||||
MSG_SD_CARD_OK 1
|
||||
MSG_SD_FILE_OPENED 1
|
||||
MSG_SD_FILE_SELECTED 1
|
||||
MSG_SD_INIT_FAIL 1
|
||||
MSG_SD_INSERTED 1
|
||||
MSG_SD_OPENROOT_FAIL 1
|
||||
MSG_SD_PRINTING_BYTE 1
|
||||
MSG_SD_REMOVED 1
|
||||
MSG_SD_SIZE 1
|
||||
MSG_SD_VOL_INIT_FAIL 1
|
||||
MSG_SD_WRITE_TO_FILE 1
|
||||
MSG_SECOND_SERIAL_OFF 1
|
||||
MSG_SECOND_SERIAL_ON 1
|
||||
MSG_SELFTEST 1
|
||||
MSG_SELFTEST_AXIS 1
|
||||
MSG_SELFTEST_AXIS_LENGTH 1
|
||||
MSG_SELFTEST_BEDHEATER 1
|
||||
MSG_SELFTEST_ENDSTOP 1
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT 1
|
||||
MSG_SELFTEST_ENDSTOPS 1
|
||||
MSG_SELFTEST_ERROR 1
|
||||
MSG_SELFTEST_EXTRUDER_FAN_SPEED 1
|
||||
MSG_SELFTEST_FANS 1
|
||||
MSG_SELFTEST_FILAMENT_SENSOR 1
|
||||
MSG_SELFTEST_HEATERTHERMISTOR 1
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT 1
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS 1
|
||||
MSG_SELFTEST_CHECK_HOTEND 1
|
||||
MSG_SELFTEST_CHECK_X 1
|
||||
MSG_SELFTEST_CHECK_Y 1
|
||||
MSG_SELFTEST_CHECK_Z 1
|
||||
MSG_SELFTEST_NOTCONNECTED 1
|
||||
MSG_SELFTEST_OK 1
|
||||
MSG_SELFTEST_PLEASECHECK 1
|
||||
MSG_SELFTEST_PRINT_FAN_SPEED 1
|
||||
MSG_SELFTEST_START 1
|
||||
MSG_SELFTEST_SWAPPED 1
|
||||
MSG_SET_TEMPERATURE 1
|
||||
MSG_SEVERE_SKEW 1
|
||||
MSG_SHOW_END_STOPS 1
|
||||
MSG_SLIGHT_SKEW 1
|
||||
MSG_SORT_ALPHA 1
|
||||
MSG_SORT_NONE 1
|
||||
MSG_SORT_TIME 1
|
||||
MSG_SORTING 1
|
||||
MSG_SPEED 1
|
||||
MSG_STACK_ERROR 1
|
||||
MSG_STATISTICS 1
|
||||
MSG_STATS_FILAMENTUSED 1
|
||||
MSG_STATS_PRINTTIME 1
|
||||
MSG_STATS_TOTALFILAMENT 1
|
||||
MSG_STATS_TOTALPRINTTIME 1
|
||||
MSG_STEPPER_TOO_HIGH 1
|
||||
MSG_SUPPORT 1
|
||||
MSG_TEMP_CAL_FAILED 1
|
||||
MSG_TEMP_CAL_WARNING 1
|
||||
MSG_TEMP_CALIBRATION_OFF 1
|
||||
MSG_TEMP_CALIBRATION_ON 1
|
||||
MSG_TEMPERATURE 1
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF 1
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON 1
|
||||
MSG_TUNE 1
|
||||
MSG_UNLOAD_ALL 1
|
||||
MSG_UNLOAD_FILAMENT_1 1
|
||||
MSG_UNLOAD_FILAMENT_2 1
|
||||
MSG_UNLOAD_FILAMENT_3 1
|
||||
MSG_UNLOAD_FILAMENT_4 1
|
||||
MSG_UNLOAD_SUCCESSFUL 1
|
||||
MSG_USED 1
|
||||
MSG_USERWAIT 1
|
||||
MSG_V2_CALIBRATION 1
|
||||
MSG_WAITING_TEMP 1
|
||||
MSG_WAITING_TEMP_PINDA 1
|
||||
MSG_WIZARD 1
|
||||
MSG_WIZARD_CLEAN_HEATBED 1
|
||||
MSG_WIZARD_FILAMENT_LOADED 1
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT 1
|
||||
MSG_WIZARD_LOAD_FILAMENT 1
|
||||
MSG_WIZARD_PLA_FILAMENT 1
|
||||
MSG_WIZARD_REPEAT_V2_CAL 1
|
||||
MSG_WIZARD_RERUN 1
|
||||
MSG_WIZARD_SELFTEST 1
|
||||
MSG_WIZARD_V2_CAL 1
|
||||
MSG_WIZARD_V2_CAL_2 1
|
||||
MSG_WIZARD_WELCOME 1
|
||||
MSG_WIZARD_WILL_PREHEAT 1
|
||||
MSG_WIZARD_XYZ_CAL 1
|
||||
MSG_WIZARD_Z_CAL 1
|
||||
MSG_X_MAX 1
|
||||
MSG_X_MIN 1
|
||||
MSG_XYZ_DETAILS 1
|
||||
MSG_Y_DISTANCE_FROM_MIN 1
|
||||
MSG_Y_MAX 1
|
||||
MSG_Y_MIN 1
|
||||
MSG_AUTO_HOME 2
|
||||
MSG_AUTO_MODE_ON 2
|
||||
MSG_BABYSTEP_Z 2
|
||||
MSG_BABYSTEP_Z_NOT_SET 2
|
||||
MSG_BED_DONE 2
|
||||
MSG_BED_HEATING 2
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED 2
|
||||
MSG_BROWNOUT_RESET 2
|
||||
MSG_CALIBRATE_Z_AUTO 2
|
||||
MSG_CONFIRM_NOZZLE_CLEAN 2
|
||||
MSG_COOLDOWN 2
|
||||
MSG_CRASH_DETECTED 2
|
||||
MSG_CRASHDETECT_NA 2
|
||||
MSG_CRASHDETECT_OFF 2
|
||||
MSG_CRASHDETECT_ON 2
|
||||
MSG_Enqueing 2
|
||||
MSG_ERR_STOPPED 2
|
||||
MSG_EXTERNAL_RESET 2
|
||||
MSG_FAN_SPEED 2
|
||||
MSG_FILAMENT_CLEAN 2
|
||||
MSG_FILAMENT_LOADING_T0 2
|
||||
MSG_FILAMENT_LOADING_T1 2
|
||||
MSG_FILAMENT_LOADING_T2 2
|
||||
MSG_FILAMENT_LOADING_T3 2
|
||||
MSG_FILAMENTCHANGE 2
|
||||
MSG_FILE_SAVED 2
|
||||
MSG_FINISHING_MOVEMENTS 2
|
||||
MSG_FOLLOW_CALIBRATION_FLOW 2
|
||||
MSG_FSENS_AUTOLOAD_NA 2
|
||||
MSG_FSENSOR_OFF 2
|
||||
MSG_FSENSOR_ON 2
|
||||
MSG_HEATING 2
|
||||
MSG_HEATING_COMPLETE 2
|
||||
MSG_HOMEYZ 2
|
||||
MSG_LOAD_FILAMENT 2
|
||||
MSG_M117_V2_CALIBRATION 2
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 2
|
||||
MSG_MENU_CALIBRATION 2
|
||||
MSG_NOZZLE 2
|
||||
MSG_PAPER 2
|
||||
MSG_PLACE_STEEL_SHEET 2
|
||||
MSG_POWERUP 2
|
||||
MSG_PRESS_TO_UNLOAD 2
|
||||
MSG_PULL_OUT_FILAMENT 2
|
||||
MSG_RECOVER_PRINT 2
|
||||
MSG_REMOVE_STEEL_SHEET 2
|
||||
MSG_SD_ERR_WRITE_TO_FILE 2
|
||||
MSG_SD_WORKDIR_FAIL 2
|
||||
MSG_SELFTEST_CHECK_BED 2
|
||||
MSG_SELFTEST_CHECK_FSENSOR 2
|
||||
MSG_SILENT_MODE_ON 2
|
||||
MSG_SOFTWARE_RESET 2
|
||||
MSG_STEALTH_MODE_OFF 2
|
||||
MSG_STEALTH_MODE_ON 2
|
||||
MSG_STOPPED 2
|
||||
MSG_TEMP_CALIBRATION_DONE 2
|
||||
MSG_UNKNOWN_COMMAND 2
|
||||
MSG_WATCH 2
|
||||
MSG_WATCHDOG_RESET 2
|
||||
MSG_WIZARD_DONE 2
|
||||
MSG_WIZARD_QUIT 2
|
||||
MSG_Z_MAX 2
|
||||
MSG_Z_MIN 2
|
||||
MSG_ZPROBE_OUT 2
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 3
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 3
|
||||
MSG_CHOOSE_EXTRUDER 3
|
||||
MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 3
|
||||
MSG_PRINT_ABORTED 3
|
||||
MSG_REFRESH 3
|
||||
MSG_SD_OPEN_FILE_FAIL 3
|
||||
MSG_SELFTEST_COOLING_FAN 3
|
||||
MSG_SELFTEST_EXTRUDER_FAN 3
|
||||
MSG_SELFTEST_FAILED 3
|
||||
MSG_SELFTEST_FAN_NO 3
|
||||
MSG_SELFTEST_FAN_YES 3
|
||||
MSG_SELFTEST_MOTOR 3
|
||||
MSG_STEEL_SHEET_CHECK 3
|
||||
MSG_STOP_PRINT 3
|
||||
MSG_TEMP_CALIBRATION 3
|
||||
MSG_UNLOAD_FILAMENT 3
|
||||
MSG_WIZARD_CALIBRATION_FAILED 3
|
||||
MSG_WIZARD_HEATING 3
|
||||
MSG_ZPROBE_ZOFFSET 3
|
||||
MSG_ENDSTOPS_HIT 4
|
||||
MSG_EXTRUDER 4
|
||||
MSG_ON 4
|
||||
MSG_POSITION_UNKNOWN 4
|
||||
MSG_SELFTEST_FAN 4
|
||||
MSG_SILENT_MODE_OFF 4
|
||||
MSG_UNLOADING_FILAMENT 4
|
||||
MSG_BED 5
|
||||
MSG_BED_LEVELING_FAILED_POINT_LOW 5
|
||||
MSG_LOADING_FILAMENT 5
|
||||
MSG_OFF 5
|
||||
MSG_SELFTEST_WIRINGERROR 5
|
||||
MSG_SETTINGS 5
|
||||
MSG_ALL 6
|
||||
MSG_ENDSTOP_HIT 6
|
||||
MSG_ENDSTOP_OPEN 6
|
||||
MSG_NO 6
|
||||
MSG_CARD_MENU 7
|
||||
MSG_PLEASE_WAIT 7
|
||||
MSG_YES 7
|
||||
MSG_OK 8
|
||||
MSG_ERROR 9
|
||||
MSG_PREHEAT_NOZZLE 9
|
||||
MSG_MAIN 12
|
||||
WELCOME_MSG 17
|
33
lang_upgrade/readme.txt
Normal file
33
lang_upgrade/readme.txt
Normal file
@ -0,0 +1,33 @@
|
||||
lang_upgrade - scripts for migration to new multilanguage support design
|
||||
|
||||
upgrade.sh - entire process:
|
||||
Run scripts: clean.sh, make_msgs.sh, find_msgs.sh, make_source.sh.
|
||||
Backup (move) all language*.h and language*.cpp files from source to folder '../lang_backup'.
|
||||
Copy folder ./source/*.* to ../Firmware, new files will be messages.h, messages.c, language.h, language.c and other source will be replaced.
|
||||
After this step should be source compilable in english version, LANG_MODE in config.h is set to 0 (primary language only)
|
||||
|
||||
|
||||
0. clean.sh
|
||||
delete all output files
|
||||
|
||||
1. make_msgs.sh
|
||||
Process all language_xx.h files and extract informations to msgs_xx.txt files in simple format.
|
||||
Every line in msgs_en.txt has following format: MSG_xx c=cc r=rr "text".
|
||||
Every line in other msgs_xx.txt has simpler format: MSG_xx "text".
|
||||
MSG_xx is original message identifier, cc is column count (originaly length) and rr is row count (originaly lines).
|
||||
Output files msgs_xx.txt are sorted by message identifier (ascending order).
|
||||
make_msgs.sh also reports number of messages in each language_xx.h file and total number of characters in program memory.
|
||||
|
||||
2. find_msgs.sh
|
||||
Find usage of each message and output listing in to file msgs_usage.txt in format: MSG_xx nn.
|
||||
MSG_xx is identifier, nn is number of occurrences. Output is sorted by number of occurrences (ascending order).
|
||||
Generate filtered msgs_en.txt and msgs_common.txt files. Each file is sorted to three output files - unused, used once and used more.
|
||||
Output files will be:
|
||||
msgs_common_unused.txt, msgs_common_used_more.txt, msgs_common_used_once.txt
|
||||
msgs_en_unused.txt, msgs_en_used_more.txt, msgs_en_used_once.txt
|
||||
|
||||
3. make_source.sh
|
||||
Copy all source files to folder ./source
|
||||
Replace all messages used once in all ./source/*.c* files directly with the english version string constant and comment at end of line.
|
||||
Generate messages.h and messages.c source files with messages used twice and more.
|
||||
Replace line '' in Marlin_main.cpp with comment.
|
13
lang_upgrade/replace_common.out
Normal file
13
lang_upgrade/replace_common.out
Normal file
@ -0,0 +1,13 @@
|
||||
MSG_ACTIVE_EXTRUDER OK
|
||||
MSG_AUTHOR OK
|
||||
MSG_COUNT_X OK
|
||||
MSG_ERR_LINE_NO OK
|
||||
MSG_ERR_LONG_EXTRUDE_STOP OK
|
||||
MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM OK
|
||||
MSG_FILE_PRINTED OK
|
||||
MSG_INVALID_EXTRUDER OK
|
||||
MSG_SD_SIZE OK
|
||||
MSG_X_MAX OK
|
||||
MSG_X_MIN OK
|
||||
MSG_Y_MAX OK
|
||||
MSG_Y_MIN OK
|
247
lang_upgrade/replace_en.out
Normal file
247
lang_upgrade/replace_en.out
Normal file
@ -0,0 +1,247 @@
|
||||
MSG_ADJUSTZ OK
|
||||
MSG_AUTOLOAD_FILAMENT OK
|
||||
MSG_AUTOLOADING_ENABLED OK
|
||||
MSG_AUTOLOADING_ONLY_IF_FSENS_ON OK
|
||||
MSG_BABYSTEPPING_X OK
|
||||
MSG_BABYSTEPPING_Y OK
|
||||
MSG_BABYSTEPPING_Z OK
|
||||
MSG_BED_CORRECTION_FRONT OK
|
||||
MSG_BED_CORRECTION_LEFT OK
|
||||
MSG_BED_CORRECTION_MENU OK
|
||||
MSG_BED_CORRECTION_REAR OK
|
||||
MSG_BED_CORRECTION_RESET OK
|
||||
MSG_BED_CORRECTION_RIGHT OK
|
||||
MSG_BED_HEATING_SAFETY_DISABLED OK
|
||||
MSG_BED_LEVELING_FAILED_POINT_HIGH OK
|
||||
MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_PERFECT OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR OK
|
||||
MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR OK
|
||||
MSG_BEGIN_FILE_LIST OK
|
||||
MSG_CALIBRATE_BED OK
|
||||
MSG_CALIBRATE_BED_RESET OK
|
||||
MSG_CALIBRATE_E OK
|
||||
MSG_CALIBRATE_PINDA OK
|
||||
MSG_CALIBRATION_PINDA_MENU OK
|
||||
MSG_CLEAN_NOZZLE_E OK
|
||||
MSG_CNG_SDCARD OK
|
||||
MSG_CONFIGURATION_VER OK
|
||||
MSG_CONFIRM_CARRIAGE_AT_THE_TOP OK
|
||||
MSG_CORRECTLY OK
|
||||
MSG_CRASH_DET_ONLY_IN_NORMAL OK
|
||||
MSG_CRASH_DET_STEALTH_FORCE_OFF OK
|
||||
MSG_CURRENT OK
|
||||
MSG_DATE OK
|
||||
MSG_DEFAULT_SETTINGS_LOADED OK
|
||||
MSG_DISABLE_STEPPERS OK
|
||||
MSG_DWELL OK
|
||||
MSG_E_CAL_KNOB OK
|
||||
MSG_END_FILE_LIST OK
|
||||
MSG_ERR_COLD_EXTRUDE_STOP OK
|
||||
MSG_ERR_CHECKSUM_MISMATCH OK
|
||||
MSG_ERR_KILLED OK
|
||||
MSG_ERR_NO_CHECKSUM OK
|
||||
MSG_ERR_NO_THERMISTORS OK
|
||||
MSG_EXTRUDER_1 OK
|
||||
MSG_EXTRUDER_2 OK
|
||||
MSG_EXTRUDER_3 OK
|
||||
MSG_EXTRUDER_4 OK
|
||||
MSG_EXTRUDER_CORRECTION OK
|
||||
MSG_EXTRUDER_CORRECTION_OFF OK
|
||||
MSG_FACTOR OK
|
||||
MSG_FANS_CHECK_OFF OK
|
||||
MSG_FANS_CHECK_ON OK
|
||||
MSG_FILAMENT_SENSOR OK
|
||||
MSG_FILE_CNT OK
|
||||
MSG_FILE_INCOMPLETE OK
|
||||
MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION OK
|
||||
MSG_FLOW OK
|
||||
MSG_FORCE_SELFTEST OK
|
||||
MSG_FREE_MEMORY OK
|
||||
MSG_FSENS_AUTOLOAD_OFF OK
|
||||
MSG_FSENS_AUTOLOAD_ON OK
|
||||
MSG_FSENS_NOT_RESPONDING OK
|
||||
MSG_FSENSOR_NA OK
|
||||
MSG_FW_VERSION_ALPHA OK
|
||||
MSG_FW_VERSION_BETA OK
|
||||
MSG_FW_VERSION_UNKNOWN OK
|
||||
MSG_HOMEYZ_DONE OK
|
||||
MSG_HOMEYZ_PROGRESS OK
|
||||
MSG_CHANGE_EXTR OK
|
||||
MSG_CHANGE_SUCCESS OK
|
||||
MSG_CHANGED_BOTH OK
|
||||
MSG_CHANGED_MOTHERBOARD OK
|
||||
MSG_CHANGED_PRINTER OK
|
||||
MSG_CHANGING_FILAMENT OK
|
||||
MSG_CHECK_IDLER OK
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 OK
|
||||
MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 OK
|
||||
MSG_INFO_EXTRUDER OK
|
||||
MSG_INFO_NOZZLE_FAN OK
|
||||
MSG_INFO_PRINT_FAN OK
|
||||
MSG_INIT_SDCARD OK
|
||||
MSG_INSERT_FILAMENT OK
|
||||
MSG_KILLED OK
|
||||
MSG_LANGUAGE_SELECT OK
|
||||
MSG_LEFT OK
|
||||
MSG_LOAD_ALL OK
|
||||
MSG_LOAD_FILAMENT_1 OK
|
||||
MSG_LOAD_FILAMENT_2 OK
|
||||
MSG_LOAD_FILAMENT_3 OK
|
||||
MSG_LOAD_FILAMENT_4 OK
|
||||
MSG_LOADING_COLOR OK
|
||||
MSG_LOOSE_PULLEY OK
|
||||
MSG_M104_INVALID_EXTRUDER OK
|
||||
MSG_M105_INVALID_EXTRUDER OK
|
||||
MSG_M109_INVALID_EXTRUDER OK
|
||||
MSG_M119_REPORT OK
|
||||
MSG_M200_INVALID_EXTRUDER OK
|
||||
MSG_M218_INVALID_EXTRUDER OK
|
||||
MSG_M221_INVALID_EXTRUDER OK
|
||||
MSG_MARK_FIL OK
|
||||
MSG_MAX OK
|
||||
MSG_MEASURED_OFFSET OK
|
||||
MSG_MEASURED_SKEW OK
|
||||
MSG_MENU_BELT_STATUS OK
|
||||
MSG_MENU_TEMPERATURES OK
|
||||
MSG_MENU_VOLTAGES OK
|
||||
MSG_MESH_BED_LEVELING OK
|
||||
MSG_MIN OK
|
||||
MSG_MOVE_AXIS OK
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP OK
|
||||
MSG_MOVE_CARRIAGE_TO_THE_TOP_Z OK
|
||||
MSG_MOVE_E OK
|
||||
MSG_MOVE_X OK
|
||||
MSG_MOVE_Y OK
|
||||
MSG_MOVE_Z OK
|
||||
MSG_NEW_FIRMWARE_AVAILABLE OK
|
||||
MSG_NEW_FIRMWARE_PLEASE_UPGRADE OK
|
||||
MSG_NO_CARD OK
|
||||
MSG_NO_MOVE OK
|
||||
MSG_NOT_COLOR OK
|
||||
MSG_NOT_LOADED OK
|
||||
MSG_NOZZLE1 OK
|
||||
MSG_NOZZLE2 OK
|
||||
MSG_PAUSE_PRINT OK
|
||||
MSG_PICK_Z OK
|
||||
MSG_PID_EXTRUDER OK
|
||||
MSG_PID_FINISHED OK
|
||||
MSG_PID_RUNNING OK
|
||||
MSG_PINDA_NOT_CALIBRATED OK
|
||||
MSG_PINDA_PREHEAT OK
|
||||
MSG_PLA_FILAMENT_LOADED OK
|
||||
MSG_PLANNER_BUFFER_BYTES OK
|
||||
MSG_PLEASE_LOAD_PLA OK
|
||||
MSG_PREHEAT OK
|
||||
MSG_PREPARE_FILAMENT OK
|
||||
MSG_PRESS OK
|
||||
MSG_PRESS_TO_PREHEAT OK
|
||||
MSG_PRINT_PAUSED OK
|
||||
MSG_PRINTER_DISCONNECTED OK
|
||||
MSG_PRUSA3D OK
|
||||
MSG_PRUSA3D_FORUM OK
|
||||
MSG_PRUSA3D_HOWTO OK
|
||||
MSG_RECOVERING_PRINT OK
|
||||
MSG_RESEND OK
|
||||
MSG_RESUME_PRINT OK
|
||||
MSG_RESUMING OK
|
||||
MSG_RESUMING_PRINT OK
|
||||
MSG_RIGHT OK
|
||||
MSG_SD_CANT_ENTER_SUBDIR OK
|
||||
MSG_SD_CANT_OPEN_SUBDIR OK
|
||||
MSG_SD_CARD_OK OK
|
||||
MSG_SD_FILE_OPENED OK
|
||||
MSG_SD_FILE_SELECTED OK
|
||||
MSG_SD_INIT_FAIL OK
|
||||
MSG_SD_INSERTED OK
|
||||
MSG_SD_OPENROOT_FAIL OK
|
||||
MSG_SD_PRINTING_BYTE OK
|
||||
MSG_SD_REMOVED OK
|
||||
MSG_SD_VOL_INIT_FAIL OK
|
||||
MSG_SD_WRITE_TO_FILE OK
|
||||
MSG_SECOND_SERIAL_OFF OK
|
||||
MSG_SECOND_SERIAL_ON OK
|
||||
MSG_SELFTEST OK
|
||||
MSG_SELFTEST_AXIS OK
|
||||
MSG_SELFTEST_AXIS_LENGTH OK
|
||||
MSG_SELFTEST_BEDHEATER OK
|
||||
MSG_SELFTEST_ENDSTOP OK
|
||||
MSG_SELFTEST_ENDSTOP_NOTHIT OK
|
||||
MSG_SELFTEST_ENDSTOPS OK
|
||||
MSG_SELFTEST_ERROR OK
|
||||
MSG_SELFTEST_EXTRUDER_FAN_SPEED OK
|
||||
MSG_SELFTEST_FANS OK
|
||||
MSG_SELFTEST_FILAMENT_SENSOR OK
|
||||
MSG_SELFTEST_HEATERTHERMISTOR OK
|
||||
MSG_SELFTEST_CHECK_ALLCORRECT OK
|
||||
MSG_SELFTEST_CHECK_ENDSTOPS OK
|
||||
MSG_SELFTEST_CHECK_HOTEND OK
|
||||
MSG_SELFTEST_CHECK_X OK
|
||||
MSG_SELFTEST_CHECK_Y OK
|
||||
MSG_SELFTEST_CHECK_Z OK
|
||||
MSG_SELFTEST_NOTCONNECTED OK
|
||||
MSG_SELFTEST_OK OK
|
||||
MSG_SELFTEST_PLEASECHECK OK
|
||||
MSG_SELFTEST_PRINT_FAN_SPEED OK
|
||||
MSG_SELFTEST_START OK
|
||||
MSG_SELFTEST_SWAPPED OK
|
||||
MSG_SET_TEMPERATURE OK
|
||||
MSG_SEVERE_SKEW OK
|
||||
MSG_SHOW_END_STOPS OK
|
||||
MSG_SLIGHT_SKEW OK
|
||||
MSG_SORT_ALPHA OK
|
||||
MSG_SORT_NONE OK
|
||||
MSG_SORT_TIME OK
|
||||
MSG_SORTING OK
|
||||
MSG_SPEED OK
|
||||
MSG_STACK_ERROR OK
|
||||
MSG_STATISTICS OK
|
||||
MSG_STATS_FILAMENTUSED OK
|
||||
MSG_STATS_PRINTTIME OK
|
||||
MSG_STATS_TOTALFILAMENT OK
|
||||
MSG_STATS_TOTALPRINTTIME OK
|
||||
MSG_STEPPER_TOO_HIGH OK
|
||||
MSG_SUPPORT OK
|
||||
MSG_TEMP_CAL_FAILED OK
|
||||
MSG_TEMP_CAL_WARNING OK
|
||||
MSG_TEMP_CALIBRATION_OFF OK
|
||||
MSG_TEMP_CALIBRATION_ON OK
|
||||
MSG_TEMPERATURE OK
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF OK
|
||||
MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON OK
|
||||
MSG_TUNE OK
|
||||
MSG_UNLOAD_ALL OK
|
||||
MSG_UNLOAD_FILAMENT_1 OK
|
||||
MSG_UNLOAD_FILAMENT_2 OK
|
||||
MSG_UNLOAD_FILAMENT_3 OK
|
||||
MSG_UNLOAD_FILAMENT_4 OK
|
||||
MSG_UNLOAD_SUCCESSFUL OK
|
||||
MSG_USED OK
|
||||
MSG_USERWAIT OK
|
||||
MSG_V2_CALIBRATION OK
|
||||
MSG_WAITING_TEMP OK
|
||||
MSG_WAITING_TEMP_PINDA OK
|
||||
MSG_WIZARD OK
|
||||
MSG_WIZARD_CLEAN_HEATBED OK
|
||||
MSG_WIZARD_FILAMENT_LOADED OK
|
||||
MSG_WIZARD_INSERT_CORRECT_FILAMENT OK
|
||||
MSG_WIZARD_LOAD_FILAMENT OK
|
||||
MSG_WIZARD_PLA_FILAMENT OK
|
||||
MSG_WIZARD_REPEAT_V2_CAL OK
|
||||
MSG_WIZARD_RERUN OK
|
||||
MSG_WIZARD_SELFTEST OK
|
||||
MSG_WIZARD_V2_CAL OK
|
||||
MSG_WIZARD_V2_CAL_2 OK
|
||||
MSG_WIZARD_WELCOME OK
|
||||
MSG_WIZARD_WILL_PREHEAT OK
|
||||
MSG_WIZARD_XYZ_CAL OK
|
||||
MSG_WIZARD_Z_CAL OK
|
||||
MSG_XYZ_DETAILS OK
|
||||
MSG_Y_DISTANCE_FROM_MIN OK
|
27
lang_upgrade/src/config.h
Normal file
27
lang_upgrade/src/config.h
Normal file
@ -0,0 +1,27 @@
|
||||
#ifndef _CONFIG_H
|
||||
#define _CONFIG_H
|
||||
|
||||
|
||||
//ADC configuration
|
||||
#define ADC_CHAN_MSK 0b0000001001011111 //used AD channels bit mask (0,1,2,3,4,6,9)
|
||||
#define ADC_CHAN_CNT 7 //number of used channels)
|
||||
#define ADC_OVRSAMPL 16 //oversampling multiplier
|
||||
#define ADC_CALLBACK adc_ready //callback function ()
|
||||
|
||||
//SM4 configuration
|
||||
#define SM4_DEFDELAY 500 //default step delay [us]
|
||||
|
||||
//TMC2130 - Trinamic stepper driver
|
||||
//pinout - hardcoded
|
||||
//spi:
|
||||
#define TMC2130_SPI_RATE 0 // fosc/4 = 4MHz
|
||||
#define TMC2130_SPCR SPI_SPCR(TMC2130_SPI_RATE, 1, 1, 1, 0)
|
||||
#define TMC2130_SPSR SPI_SPSR(TMC2130_SPI_RATE)
|
||||
|
||||
//LANG - Multi-language support
|
||||
#define LANG_MODE 0 // primary language only
|
||||
//#define LANG_MODE 1 // sec. language support
|
||||
#define LANG_SIZE_RESERVED 0x3000 // reserved space for secondary language (12kb)
|
||||
|
||||
|
||||
#endif //_CONFIG_H
|
63
lang_upgrade/src/language.c
Normal file
63
lang_upgrade/src/language.c
Normal file
@ -0,0 +1,63 @@
|
||||
//language.c
|
||||
#include "language.h"
|
||||
#include <inttypes.h>
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
|
||||
// Currectly active language selection.
|
||||
unsigned char lang_selected = 0;
|
||||
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
#else //(LANG_MODE == 0)
|
||||
//reserved xx kbytes for secondary language table
|
||||
static const char _SEC_LANG[LANG_SIZE_RESERVED] PROGMEM_I2 = "_SEC_LANG";
|
||||
#endif //(LANG_MODE == 0)
|
||||
|
||||
//lang_table_t structure - 16byte header
|
||||
typedef struct
|
||||
{
|
||||
struct
|
||||
{
|
||||
uint32_t magic;
|
||||
uint16_t size;
|
||||
uint16_t count;
|
||||
uint16_t checksum;
|
||||
uint16_t reserved0;
|
||||
uint32_t reserved1;
|
||||
} header;
|
||||
uint16_t table[];
|
||||
} lang_table_t;
|
||||
|
||||
//lang_table pointer
|
||||
lang_table_t* lang_table = 0;
|
||||
|
||||
|
||||
const char* lang_get_translation(const char* s)
|
||||
{
|
||||
if (lang_selected == 0) return s + 2; //primary language selected
|
||||
if (lang_table == 0) return s + 2; //sec. lang table not found
|
||||
uint16_t ui = pgm_read_word(((uint16_t*)s)); //read string id
|
||||
if (ui == 0xffff) return s + 2; //translation not found
|
||||
ui = pgm_read_word(((uint16_t*)(((char*)lang_table + 16 + ui*2)))); //read relative offset
|
||||
return (const char*)((char*)lang_table + ui + 16); //return calculated pointer
|
||||
}
|
||||
|
||||
const char* lang_select(unsigned char lang)
|
||||
{
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
return 0;
|
||||
#else //(LANG_MODE == 0)
|
||||
if (lang == 0) //primary language
|
||||
{
|
||||
lang_table = 0;
|
||||
lang_selected = 0;
|
||||
return;
|
||||
}
|
||||
uint16_t ui = (uint16_t)&_SEC_LANG; //pointer to _SEC_LANG reserved space
|
||||
ui += 0x0100; //add 1 page
|
||||
ui &= 0xff00; //align to page
|
||||
lang_table = ui; //set table pointer
|
||||
ui = pgm_read_word(((uint16_t*)(((char*)lang_table + 16)))); //read relative offset of first string (language name)
|
||||
return (const char*)((char*)lang_table + ui + 16); //return calculated pointer
|
||||
#endif //(LANG_MODE == 0)
|
||||
}
|
87
lang_upgrade/src/language.h
Normal file
87
lang_upgrade/src/language.h
Normal file
@ -0,0 +1,87 @@
|
||||
//language.h
|
||||
#ifndef LANGUAGE_H
|
||||
#define LANGUAGE_H
|
||||
|
||||
#include "config.h"
|
||||
|
||||
#define PROTOCOL_VERSION "1.0"
|
||||
|
||||
#ifdef CUSTOM_MENDEL_NAME
|
||||
// #define CUSTOM_MENDEL_NAME CUSTOM_MENDEL_NAME
|
||||
#else
|
||||
#define MACHINE_NAME "Mendel"
|
||||
#endif
|
||||
|
||||
#ifndef MACHINE_UUID
|
||||
#define MACHINE_UUID "00000000-0000-0000-0000-000000000000"
|
||||
#endif
|
||||
|
||||
#define MSG_FW_VERSION "Firmware"
|
||||
|
||||
#define STRINGIFY_(n) #n
|
||||
#define STRINGIFY(n) STRINGIFY_(n)
|
||||
|
||||
#if (LANG_MODE == 0)
|
||||
//#define _i PSTR
|
||||
//#define _I(s) (__extension__({static const char __c[] __attribute__((section("Txt_i"))) = s; &__c[0];}))
|
||||
#endif //(LANG_MODE == 0)
|
||||
|
||||
//section progmem0 will be used for localized translated strings
|
||||
#define PROGMEM_I2 __attribute__((section(".progmem0")))
|
||||
//section progmem1 will be used for localized strings in english
|
||||
#define PROGMEM_I1 __attribute__((section(".progmem1")))
|
||||
//section progmem2 will be used for not localized strings in english
|
||||
#define PROGMEM_N1 __attribute__((section(".progmem2")))
|
||||
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
#define _I(s) (__extension__({static const char __c[] PROGMEM_I1 = s; &__c[0];}))
|
||||
#define ISTR(s) s
|
||||
#define _i(s) _I(s)
|
||||
#define _T(s) s
|
||||
#else //(LANG_MODE == 0)
|
||||
#define _I(s) (__extension__({static const char __c[] PROGMEM_I1 = "\xff\xff"s; &__c[0];}))
|
||||
#define ISTR(s) "\xff\xff"s
|
||||
#define _i(s) lang_get_translation(_I(s))
|
||||
#define _T(s) lang_get_translation(s)
|
||||
#endif //(LANG_MODE == 0)
|
||||
#define _N(s) (__extension__({static const char __c[] PROGMEM_N1 = s; &__c[0];}))
|
||||
#define _n(s) _N(s)
|
||||
|
||||
|
||||
// Language indices into their particular symbol tables.
|
||||
#define LANG_ID_EN 0
|
||||
#define LANG_ID_CZ 1
|
||||
// Language is not defined and it shall be selected from the menu.
|
||||
#define LANG_ID_FORCE_SELECTION 254
|
||||
// Language is not defined on a virgin RAMBo board.
|
||||
#define LANG_ID_UNDEFINED 255
|
||||
|
||||
// Default language ID, if no language is selected.
|
||||
#define LANG_ID_DEFAULT LANG_ID_CZ
|
||||
|
||||
// Number of languages available in the language table.
|
||||
#define LANG_NUM 2
|
||||
|
||||
|
||||
#if defined(__cplusplus)
|
||||
extern "C" {
|
||||
#endif //defined(__cplusplus)
|
||||
|
||||
// Currectly active language selection.
|
||||
extern unsigned char lang_selected;
|
||||
|
||||
extern const char* lang_get_translation(const char* s);
|
||||
extern const char* lang_select(unsigned char lang);
|
||||
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif //defined(__cplusplus)
|
||||
|
||||
#define CAT2(_s1, _s2) _s1
|
||||
#define CAT4(_s1, _s2, _s3, _s4) _s1
|
||||
#define MSG_LANGUAGE_NAME_EXPLICIT(i) ((i==0)?PSTR("ENG"):PSTR("CZE"))
|
||||
|
||||
#include "messages.h"
|
||||
|
||||
#endif //__LANGUAGE_H
|
||||
|
9
lang_upgrade/src/messages.c
Normal file
9
lang_upgrade/src/messages.c
Normal file
@ -0,0 +1,9 @@
|
||||
//messages.c
|
||||
#include "language.h"
|
||||
|
||||
//this is because we need include Configuration_prusa.h (CUSTOM_MENDEL_NAME)
|
||||
#define bool char
|
||||
#define true 1
|
||||
#define false 0
|
||||
#include "Configuration_prusa.h"
|
||||
|
6
lang_upgrade/src/messages.h
Normal file
6
lang_upgrade/src/messages.h
Normal file
@ -0,0 +1,6 @@
|
||||
//messages.h
|
||||
|
||||
// Common serial messages
|
||||
#define MSG_MARLIN "Marlin"
|
||||
|
||||
// LCD Menu Messages
|
Loading…
Reference in New Issue
Block a user