Merge branch 'MK3' into MK3_TONE
This commit is contained in:
commit
56193ea252
14
.editorconfig
Normal file
14
.editorconfig
Normal file
@ -0,0 +1,14 @@
|
||||
#-*-mode:conf-*-
|
||||
# editorconfig file (see EditorConfig.org)
|
||||
|
||||
root = true
|
||||
|
||||
[*]
|
||||
end_of_line = lf
|
||||
insert_final_newline = true
|
||||
charset = utf-8
|
||||
trim_trailing_whitespace = true
|
||||
indent_style = space
|
||||
indent_size = 4
|
||||
tab_width = 4
|
||||
max_line_length = 100
|
@ -16,8 +16,8 @@ extern uint16_t nPrinterType;
|
||||
extern PGM_P sPrinterName;
|
||||
|
||||
// Firmware version
|
||||
#define FW_VERSION "3.7.2"
|
||||
#define FW_COMMIT_NR 2363
|
||||
#define FW_VERSION "3.8.1"
|
||||
#define FW_COMMIT_NR 2869
|
||||
// FW_VERSION_UNKNOWN means this is an unofficial build.
|
||||
// The firmware should only be checked into github with this symbol.
|
||||
#define FW_DEV_VERSION FW_VERSION_UNKNOWN
|
||||
@ -113,11 +113,6 @@ extern PGM_P sPrinterName;
|
||||
// #define PS_DEFAULT_OFF
|
||||
|
||||
|
||||
|
||||
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
|
||||
//#define TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10
|
||||
|
||||
// Actual temperature must be close to target for this long before M109 returns success
|
||||
#define TEMP_RESIDENCY_TIME 3 // (seconds)
|
||||
#define TEMP_HYSTERESIS 5 // (degC) range of +/- temperatures considered "close" to the target one
|
||||
@ -291,6 +286,8 @@ your extruder heater takes 2 minutes to hit the target on heating.
|
||||
|
||||
#define Z_HEIGHT_HIDE_LIVE_ADJUST_MENU 2.0f
|
||||
|
||||
#define HOME_Z_SEARCH_THRESHOLD 0.15f // Threshold of the Z height in calibration
|
||||
|
||||
//============================= Bed Auto Leveling ===========================
|
||||
|
||||
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (remove // at the start of the line)
|
||||
@ -348,7 +345,7 @@ your extruder heater takes 2 minutes to hit the target on heating.
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER -29
|
||||
#define Z_PROBE_OFFSET_FROM_EXTRUDER -12.35
|
||||
|
||||
#define Z_RAISE_BEFORE_HOMING 4 // (in mm) Raise Z before homing (G28) for Probe Clearance.
|
||||
#define Z_RAISE_BEFORE_HOMING 5 // (in mm) Raise Z before homing (G28) for Probe Clearance.
|
||||
// Be sure you have this distance over your Z_MAX_POS in case
|
||||
|
||||
#define XY_TRAVEL_SPEED 8000 // X and Y axis travel speed between probes, in mm/min
|
||||
@ -552,6 +549,12 @@ enum CalibrationStatus
|
||||
CALIBRATION_STATUS_UNKNOWN = 0,
|
||||
};
|
||||
|
||||
// Try to maintain a minimum distance from the bed even when Z is
|
||||
// unknown when doing the following operations
|
||||
#define MIN_Z_FOR_LOAD 50
|
||||
#define MIN_Z_FOR_UNLOAD 20
|
||||
#define MIN_Z_FOR_PREHEAT 10
|
||||
|
||||
#include "Configuration_adv.h"
|
||||
#include "thermistortables.h"
|
||||
|
||||
|
@ -10,14 +10,6 @@
|
||||
#endif
|
||||
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
|
||||
|
||||
//// Heating sanity check:
|
||||
// This waits for the watch period in milliseconds whenever an M104 or M109 increases the target temperatureLCD_PROGRESS_BAR
|
||||
// If the temperature has not increased at the end of that period, the target temperature is set to zero.
|
||||
// It can be reset with another M104/M109. This check is also only triggered if the target temperature and the current temperature
|
||||
// differ by at least 2x WATCH_TEMP_INCREASE
|
||||
//#define WATCH_TEMP_PERIOD 40000 //40 seconds
|
||||
//#define WATCH_TEMP_INCREASE 10 //Heat up at least 10 degree in 20 seconds
|
||||
|
||||
#ifdef PIDTEMP
|
||||
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
|
||||
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
|
||||
@ -400,10 +392,6 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||
//============================= Define Defines ============================
|
||||
//===========================================================================
|
||||
|
||||
#if EXTRUDERS > 1 && defined TEMP_SENSOR_1_AS_REDUNDANT
|
||||
#error "You cannot use TEMP_SENSOR_1_AS_REDUNDANT if EXTRUDERS > 1"
|
||||
#endif
|
||||
|
||||
#if EXTRUDERS > 1 && defined HEATERS_PARALLEL
|
||||
#error "You cannot use HEATERS_PARALLEL if EXTRUDERS > 1"
|
||||
#endif
|
||||
|
@ -296,6 +296,7 @@ void setPwmFrequency(uint8_t pin, int val);
|
||||
extern bool fans_check_enabled;
|
||||
extern float homing_feedrate[];
|
||||
extern bool axis_relative_modes[];
|
||||
extern float feedrate;
|
||||
extern int feedmultiply;
|
||||
extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders
|
||||
extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
|
||||
@ -308,11 +309,6 @@ extern bool axis_known_position[3];
|
||||
extern int fanSpeed;
|
||||
extern int8_t lcd_change_fil_state;
|
||||
|
||||
const char smooth1[] PROGMEM = "Smooth1";
|
||||
const char smooth2[] PROGMEM = "Smooth2";
|
||||
const char textured[] PROGMEM = "Textur1";
|
||||
const char *const defaultSheetNames[] PROGMEM = {smooth1,smooth2,textured};
|
||||
|
||||
#ifdef TMC2130
|
||||
void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0);
|
||||
#else
|
||||
@ -363,9 +359,6 @@ extern int fan_speed[2];
|
||||
// Handling multiple extruders pins
|
||||
extern uint8_t active_extruder;
|
||||
|
||||
|
||||
#endif
|
||||
|
||||
//Long pause
|
||||
extern unsigned long pause_time;
|
||||
extern unsigned long start_pause_print;
|
||||
@ -381,6 +374,10 @@ extern char dir_names[3][9];
|
||||
extern int8_t lcd_change_fil_state;
|
||||
// save/restore printing
|
||||
extern bool saved_printing;
|
||||
extern uint8_t saved_printing_type;
|
||||
#define PRINTING_TYPE_SD 0
|
||||
#define PRINTING_TYPE_USB 1
|
||||
#define PRINTING_TYPE_NONE 2
|
||||
|
||||
//save/restore printing in case that mmu is not responding
|
||||
extern bool mmu_print_saved;
|
||||
@ -396,12 +393,10 @@ extern uint16_t print_time_remaining_silent;
|
||||
extern uint16_t mcode_in_progress;
|
||||
extern uint16_t gcode_in_progress;
|
||||
|
||||
extern bool wizard_active; //autoload temporarily disabled during wizard
|
||||
|
||||
extern LongTimer safetyTimer;
|
||||
|
||||
#define PRINT_PERCENT_DONE_INIT 0xff
|
||||
#define PRINTER_ACTIVE (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == CustomMsg::TempCal) || saved_printing || (lcd_commands_type == LcdCommands::Layer1Cal) || card.paused || mmu_print_saved)
|
||||
#define PRINTER_ACTIVE (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == CustomMsg::TempCal) || saved_printing || (lcd_commands_type == LcdCommands::Layer1Cal) || mmu_print_saved)
|
||||
|
||||
//! Beware - mcode_in_progress is set as soon as the command gets really processed,
|
||||
//! which is not the same as posting the M600 command into the command queue
|
||||
@ -430,8 +425,6 @@ void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_
|
||||
void bed_check(float x_dimension, float y_dimension, int x_points_num, int y_points_num, float shift_x, float shift_y);
|
||||
#endif //HEATBED_ANALYSIS
|
||||
float temp_comp_interpolation(float temperature);
|
||||
void temp_compensation_apply();
|
||||
void temp_compensation_start();
|
||||
void show_fw_version_warnings();
|
||||
uint8_t check_printer_version();
|
||||
|
||||
@ -518,4 +511,6 @@ void M600_wait_for_user(float HotendTempBckp);
|
||||
void M600_check_state(float nozzle_temp);
|
||||
void load_filament_final_feed();
|
||||
void marlin_wait_for_click();
|
||||
void marlin_rise_z(void);
|
||||
void raise_z_above(float target, bool plan=true);
|
||||
|
||||
#endif
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -394,7 +394,10 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) {
|
||||
i = 8; // place for extension
|
||||
} else {
|
||||
// illegal FAT characters
|
||||
PGM_P p = PSTR("|<>^+=?/[];,*\"\\");
|
||||
//PGM_P p = PSTR("|<>^+=?/[];,*\"\\");
|
||||
// 2019-08-27 really?
|
||||
// Microsoft defines, that only a subset of these characters is not allowed.
|
||||
PGM_P p = PSTR("|<>?/*\"\\");
|
||||
uint8_t b;
|
||||
while ((b = pgm_read_byte(p++))) if (b == c) goto fail;
|
||||
// check size and only allow ASCII printable characters
|
||||
|
@ -4,6 +4,7 @@
|
||||
#include <stdio.h>
|
||||
#include <avr/io.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include "pins.h"
|
||||
|
||||
uint8_t adc_state;
|
||||
uint8_t adc_count;
|
||||
@ -24,8 +25,8 @@ void adc_init(void)
|
||||
ADMUX |= (1 << REFS0);
|
||||
ADCSRA |= (1 << ADEN);
|
||||
// ADCSRA |= (1 << ADIF) | (1 << ADSC);
|
||||
DIDR0 = (ADC_CHAN_MSK & 0xff);
|
||||
DIDR2 = (ADC_CHAN_MSK >> 8);
|
||||
DIDR0 = ((ADC_CHAN_MSK & ADC_DIDR_MSK) & 0xff);
|
||||
DIDR2 = ((ADC_CHAN_MSK & ADC_DIDR_MSK) >> 8);
|
||||
adc_reset();
|
||||
// adc_sim_mask = 0b0101;
|
||||
// adc_sim_mask = 0b100101;
|
||||
|
@ -25,7 +25,6 @@ CardReader::CardReader()
|
||||
sdpos = 0;
|
||||
sdprinting = false;
|
||||
cardOK = false;
|
||||
paused = false;
|
||||
saving = false;
|
||||
logging = false;
|
||||
autostart_atmillis=0;
|
||||
@ -137,8 +136,8 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
||||
SERIAL_ECHOPGM("Access date: ");
|
||||
MYSERIAL.println(p.lastAccessDate);
|
||||
SERIAL_ECHOLNPGM("");*/
|
||||
creationDate = p.creationDate;
|
||||
creationTime = p.creationTime;
|
||||
modificationDate = p.lastWriteDate;
|
||||
modificationTime = p.lastWriteTime;
|
||||
//writeDate = p.lastAccessDate;
|
||||
if (match != NULL) {
|
||||
if (strcasecmp(match, filename) == 0) return;
|
||||
@ -203,6 +202,7 @@ void CardReader::initsd()
|
||||
}
|
||||
workDir=root;
|
||||
curDir=&root;
|
||||
workDirDepth = 0;
|
||||
|
||||
#ifdef SDCARD_SORT_ALPHA
|
||||
presort();
|
||||
@ -241,24 +241,13 @@ void CardReader::startFileprint()
|
||||
if(cardOK)
|
||||
{
|
||||
sdprinting = true;
|
||||
paused = false;
|
||||
Stopped = false;
|
||||
Stopped = false;
|
||||
#ifdef SDCARD_SORT_ALPHA
|
||||
//flush_presort();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void CardReader::pauseSDPrint()
|
||||
{
|
||||
if(sdprinting)
|
||||
{
|
||||
sdprinting = false;
|
||||
paused = true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void CardReader::openLogFile(const char* name)
|
||||
{
|
||||
logging = true;
|
||||
@ -407,9 +396,7 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru
|
||||
SERIAL_ECHOLN(name);
|
||||
}
|
||||
sdprinting = false;
|
||||
paused = false;
|
||||
|
||||
|
||||
|
||||
SdFile myDir;
|
||||
const char *fname=name;
|
||||
diveSubfolder(fname,myDir);
|
||||
@ -491,24 +478,27 @@ uint32_t CardReader::getFileSize()
|
||||
|
||||
void CardReader::getStatus()
|
||||
{
|
||||
if(sdprinting){
|
||||
SERIAL_PROTOCOL(longFilename);
|
||||
SERIAL_PROTOCOLPGM("\n");
|
||||
SERIAL_PROTOCOLRPGM(_N("SD printing byte "));////MSG_SD_PRINTING_BYTE
|
||||
SERIAL_PROTOCOL(sdpos);
|
||||
SERIAL_PROTOCOLPGM("/");
|
||||
SERIAL_PROTOCOLLN(filesize);
|
||||
uint16_t time = _millis()/60000 - starttime/60000;
|
||||
SERIAL_PROTOCOL(itostr2(time/60));
|
||||
SERIAL_PROTOCOL(':');
|
||||
SERIAL_PROTOCOL(itostr2(time%60));
|
||||
SERIAL_PROTOCOLPGM("\n");
|
||||
}
|
||||
else if (paused) {
|
||||
SERIAL_PROTOCOLLNPGM("SD print paused");
|
||||
}
|
||||
else if (saved_printing) {
|
||||
SERIAL_PROTOCOLLNPGM("Print saved");
|
||||
if(sdprinting)
|
||||
{
|
||||
if (isPrintPaused) {
|
||||
SERIAL_PROTOCOLLNPGM("SD print paused");
|
||||
}
|
||||
else if (saved_printing) {
|
||||
SERIAL_PROTOCOLLNPGM("Print saved");
|
||||
}
|
||||
else {
|
||||
SERIAL_PROTOCOL(longFilename);
|
||||
SERIAL_PROTOCOLPGM("\n");
|
||||
SERIAL_PROTOCOLRPGM(_N("SD printing byte "));////MSG_SD_PRINTING_BYTE
|
||||
SERIAL_PROTOCOL(sdpos);
|
||||
SERIAL_PROTOCOLPGM("/");
|
||||
SERIAL_PROTOCOLLN(filesize);
|
||||
uint16_t time = _millis()/60000 - starttime/60000;
|
||||
SERIAL_PROTOCOL(itostr2(time/60));
|
||||
SERIAL_PROTOCOL(':');
|
||||
SERIAL_PROTOCOL(itostr2(time%60));
|
||||
SERIAL_PROTOCOLPGM("\n");
|
||||
}
|
||||
}
|
||||
else {
|
||||
SERIAL_PROTOCOLLNPGM("Not SD printing");
|
||||
@ -762,8 +752,8 @@ void CardReader::presort() {
|
||||
#endif
|
||||
#elif SDSORT_USES_STACK
|
||||
char sortnames[fileCnt][LONG_FILENAME_LENGTH];
|
||||
uint16_t creation_time[fileCnt];
|
||||
uint16_t creation_date[fileCnt];
|
||||
uint16_t modification_time[fileCnt];
|
||||
uint16_t modification_date[fileCnt];
|
||||
#endif
|
||||
|
||||
// Folder sorting needs 1 bit per entry for flags.
|
||||
@ -783,8 +773,8 @@ void CardReader::presort() {
|
||||
// retaining only two filenames at a time. This is very
|
||||
// slow but is safest and uses minimal RAM.
|
||||
char name1[LONG_FILENAME_LENGTH + 1];
|
||||
uint16_t creation_time_bckp;
|
||||
uint16_t creation_date_bckp;
|
||||
uint16_t modification_time_bckp;
|
||||
uint16_t modification_date_bckp;
|
||||
|
||||
#endif
|
||||
position = 0;
|
||||
@ -810,8 +800,8 @@ void CardReader::presort() {
|
||||
#else
|
||||
// Copy filenames into the static array
|
||||
strcpy(sortnames[i], LONGEST_FILENAME);
|
||||
creation_time[i] = creationTime;
|
||||
creation_date[i] = creationDate;
|
||||
modification_time[i] = modificationTime;
|
||||
modification_date[i] = modificationDate;
|
||||
#if SDSORT_CACHE_NAMES
|
||||
strcpy(sortshort[i], filename);
|
||||
#endif
|
||||
@ -836,12 +826,12 @@ void CardReader::presort() {
|
||||
// Compare names from the array or just the two buffered names
|
||||
#if SDSORT_USES_RAM
|
||||
#define _SORT_CMP_NODIR() (strcasecmp(sortnames[o1], sortnames[o2]) > 0)
|
||||
#define _SORT_CMP_TIME_NODIR() (((creation_date[o1] == creation_date[o2]) && (creation_time[o1] < creation_time[o2])) || \
|
||||
(creation_date[o1] < creation_date [o2]))
|
||||
#define _SORT_CMP_TIME_NODIR() (((modification_date[o1] == modification_date[o2]) && (modification_time[o1] < modification_time[o2])) || \
|
||||
(modification_date[o1] < modification_date [o2]))
|
||||
#else
|
||||
#define _SORT_CMP_NODIR() (strcasecmp(name1, name2) > 0) //true if lowercase(name1) > lowercase(name2)
|
||||
#define _SORT_CMP_TIME_NODIR() (((creation_date_bckp == creationDate) && (creation_time_bckp > creationTime)) || \
|
||||
(creation_date_bckp > creationDate))
|
||||
#define _SORT_CMP_TIME_NODIR() (((modification_date_bckp == modificationDate) && (modification_time_bckp > modificationTime)) || \
|
||||
(modification_date_bckp > modificationDate))
|
||||
|
||||
#endif
|
||||
|
||||
@ -892,8 +882,8 @@ void CardReader::presort() {
|
||||
counter++;
|
||||
getfilename_simple(positions[o1]);
|
||||
strcpy(name1, LONGEST_FILENAME); // save (or getfilename below will trounce it)
|
||||
creation_date_bckp = creationDate;
|
||||
creation_time_bckp = creationTime;
|
||||
modification_date_bckp = modificationDate;
|
||||
modification_time_bckp = modificationTime;
|
||||
#if HAS_FOLDER_SORTING
|
||||
bool dir1 = filenameIsDir;
|
||||
#endif
|
||||
|
@ -25,7 +25,6 @@ public:
|
||||
void closefile(bool store_location=false);
|
||||
void release();
|
||||
void startFileprint();
|
||||
void pauseSDPrint();
|
||||
uint32_t getFileSize();
|
||||
void getStatus();
|
||||
void printingHasFinished();
|
||||
@ -75,9 +74,8 @@ public:
|
||||
bool logging;
|
||||
bool sdprinting ;
|
||||
bool cardOK ;
|
||||
bool paused ;
|
||||
char filename[13];
|
||||
uint16_t creationTime, creationDate;
|
||||
uint16_t modificationTime, modificationDate;
|
||||
uint32_t cluster, position;
|
||||
char longFilename[LONG_FILENAME_LENGTH];
|
||||
bool filenameIsDir;
|
||||
@ -114,8 +112,8 @@ private:
|
||||
#endif
|
||||
#elif !SDSORT_USES_STACK
|
||||
char sortnames[SDSORT_LIMIT][FILENAME_LENGTH];
|
||||
uint16_t creation_time[SDSORT_LIMIT];
|
||||
uint16_t creation_date[SDSORT_LIMIT];
|
||||
uint16_t modification_time[SDSORT_LIMIT];
|
||||
uint16_t modification_date[SDSORT_LIMIT];
|
||||
#endif
|
||||
|
||||
// Folder sorting uses an isDir array when caching items.
|
||||
|
@ -224,9 +224,13 @@ void cmdqueue_dump_to_serial_single_line(int nr, const char *p)
|
||||
SERIAL_ECHOPGM("Entry nr: ");
|
||||
SERIAL_ECHO(nr);
|
||||
SERIAL_ECHOPGM(", type: ");
|
||||
SERIAL_ECHO(int(*p));
|
||||
int type = *p;
|
||||
SERIAL_ECHO(type);
|
||||
SERIAL_ECHOPGM(", size: ");
|
||||
unsigned int size = *(unsigned int*)(p + 1);
|
||||
SERIAL_ECHO(size);
|
||||
SERIAL_ECHOPGM(", cmd: ");
|
||||
SERIAL_ECHO(p+1);
|
||||
SERIAL_ECHO(p + CMDHDRSIZE);
|
||||
SERIAL_ECHOLNPGM("");
|
||||
}
|
||||
|
||||
@ -247,7 +251,7 @@ void cmdqueue_dump_to_serial()
|
||||
for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + bufindw; ++ nr) {
|
||||
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||
// Skip the command.
|
||||
for (++p; *p != 0; ++ p);
|
||||
for (p += CMDHDRSIZE; *p != 0; ++ p);
|
||||
// Skip the gaps.
|
||||
for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
|
||||
}
|
||||
@ -255,14 +259,14 @@ void cmdqueue_dump_to_serial()
|
||||
for (const char *p = cmdbuffer + bufindr; p < cmdbuffer + sizeof(cmdbuffer); ++ nr) {
|
||||
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||
// Skip the command.
|
||||
for (++p; *p != 0; ++ p);
|
||||
for (p += CMDHDRSIZE; *p != 0; ++ p);
|
||||
// Skip the gaps.
|
||||
for (++p; p < cmdbuffer + sizeof(cmdbuffer) && *p == 0; ++ p);
|
||||
}
|
||||
for (const char *p = cmdbuffer; p < cmdbuffer + bufindw; ++ nr) {
|
||||
cmdqueue_dump_to_serial_single_line(nr, p);
|
||||
// Skip the command.
|
||||
for (++p; *p != 0; ++ p);
|
||||
for (p += CMDHDRSIZE; *p != 0; ++ p);
|
||||
// Skip the gaps.
|
||||
for (++p; p < cmdbuffer + bufindw && *p == 0; ++ p);
|
||||
}
|
||||
@ -578,30 +582,8 @@ void get_command()
|
||||
((serial_char == '#' || serial_char == ':') && comment_mode == false) ||
|
||||
serial_count >= (MAX_CMD_SIZE - 1) || n==-1)
|
||||
{
|
||||
if(card.eof()){
|
||||
SERIAL_PROTOCOLLNRPGM(_n("Done printing file"));////MSG_FILE_PRINTED
|
||||
stoptime=_millis();
|
||||
char time[30];
|
||||
unsigned long t=(stoptime-starttime-pause_time)/1000;
|
||||
pause_time = 0;
|
||||
int hours, minutes;
|
||||
minutes=(t/60)%60;
|
||||
hours=t/60/60;
|
||||
save_statistics(total_filament_used, t);
|
||||
sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLN(time);
|
||||
lcd_setstatus(time);
|
||||
card.printingHasFinished();
|
||||
card.checkautostart(true);
|
||||
if(card.eof()) break;
|
||||
|
||||
if (farm_mode)
|
||||
{
|
||||
prusa_statistics(6);
|
||||
lcd_commands_type = LcdCommands::FarmModeConfirm;
|
||||
}
|
||||
|
||||
}
|
||||
if(serial_char=='#')
|
||||
stop_buffering=true;
|
||||
|
||||
@ -659,6 +641,37 @@ void get_command()
|
||||
else if(!comment_mode) cmdbuffer[bufindw+CMDHDRSIZE+serial_count++] = serial_char;
|
||||
}
|
||||
}
|
||||
if(card.eof())
|
||||
{
|
||||
// file was fully buffered, but commands might still need to be planned!
|
||||
// do *not* clear sdprinting until all SD commands are consumed to ensure
|
||||
// SD state can be resumed from a saved printing state. sdprinting is only
|
||||
// cleared by printingHasFinished after peforming all remaining moves.
|
||||
if(!cmdqueue_calc_sd_length())
|
||||
{
|
||||
SERIAL_PROTOCOLLNRPGM(_n("Done printing file"));////MSG_FILE_PRINTED
|
||||
stoptime=_millis();
|
||||
char time[30];
|
||||
unsigned long t=(stoptime-starttime-pause_time)/1000;
|
||||
pause_time = 0;
|
||||
int hours, minutes;
|
||||
minutes=(t/60)%60;
|
||||
hours=t/60/60;
|
||||
save_statistics(total_filament_used, t);
|
||||
sprintf_P(time, PSTR("%i hours %i minutes"),hours, minutes);
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLN(time);
|
||||
lcd_setstatus(time);
|
||||
card.printingHasFinished();
|
||||
card.checkautostart(true);
|
||||
|
||||
if (farm_mode)
|
||||
{
|
||||
prusa_statistics(6);
|
||||
lcd_commands_type = LcdCommands::FarmModeConfirm;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif //SDSUPPORT
|
||||
}
|
||||
|
@ -45,6 +45,8 @@ extern bool cmdbuffer_front_already_processed;
|
||||
// Debugging information will be sent to serial line.
|
||||
//#define CMDBUFFER_DEBUG
|
||||
|
||||
extern uint32_t sdpos_atomic;
|
||||
|
||||
extern int serial_count;
|
||||
extern boolean comment_mode;
|
||||
extern char *strchr_pointer;
|
||||
|
@ -2,9 +2,21 @@
|
||||
#define _CONFIG_H
|
||||
|
||||
|
||||
#include "Configuration_prusa.h"
|
||||
#include "pins.h"
|
||||
|
||||
#define IR_SENSOR_ANALOG (defined(VOLT_IR_PIN) && defined(IR_SENSOR))
|
||||
|
||||
//ADC configuration
|
||||
#if !IR_SENSOR_ANALOG
|
||||
#define ADC_CHAN_MSK 0b0000001001011111 //used AD channels bit mask (0,1,2,3,4,6,9)
|
||||
#define ADC_DIDR_MSK 0b0000001001011111 //AD channels DIDR mask (1 ~ disabled digital input)
|
||||
#define ADC_CHAN_CNT 7 //number of used channels)
|
||||
#else //!IR_SENSOR_ANALOG
|
||||
#define ADC_CHAN_MSK 0b0000001101011111 //used AD channels bit mask (0,1,2,3,4,6,8,9)
|
||||
#define ADC_DIDR_MSK 0b0000001001011111 //AD channels DIDR mask (1 ~ disabled digital input)
|
||||
#define ADC_CHAN_CNT 8 //number of used channels)
|
||||
#endif //!IR_SENSOR_ANALOG
|
||||
#define ADC_OVRSAMPL 16 //oversampling multiplier
|
||||
#define ADC_CALLBACK adc_ready //callback function ()
|
||||
|
||||
@ -42,14 +54,11 @@
|
||||
#define W25X20CL_SPCR SPI_SPCR(W25X20CL_SPI_RATE, 1, 1, 1, 0)
|
||||
#define W25X20CL_SPSR SPI_SPSR(W25X20CL_SPI_RATE)
|
||||
|
||||
#include "boards.h"
|
||||
#include "Configuration_prusa.h"
|
||||
|
||||
//LANG - Multi-language support
|
||||
//#define LANG_MODE 0 // primary language only
|
||||
//define LANG_MODE 0 // primary language only
|
||||
#define LANG_MODE 1 // sec. language support
|
||||
|
||||
#define LANG_SIZE_RESERVED 0x2800 // reserved space for secondary language (10240 bytes)
|
||||
#define LANG_SIZE_RESERVED 0x3000 // reserved space for secondary language (12288 bytes)
|
||||
|
||||
|
||||
#endif //_CONFIG_H
|
||||
|
@ -41,7 +41,8 @@ bool eeprom_is_uninitialized<char>(char *address)
|
||||
return (0xff == eeprom_read_byte(reinterpret_cast<uint8_t*>(address)));
|
||||
}
|
||||
|
||||
bool is_sheet_initialized(uint8_t sheet_num){
|
||||
bool eeprom_is_sheet_initialized(uint8_t sheet_num)
|
||||
{
|
||||
return (0xffff != eeprom_read_word(reinterpret_cast<uint16_t*>(&(EEPROM_Sheets_base->
|
||||
s[sheet_num].z_offset))));
|
||||
}
|
||||
@ -61,7 +62,14 @@ void eeprom_init()
|
||||
if (eeprom_read_word((uint16_t*)EEPROM_MMU_LOAD_FAIL_TOT) == 0xffff) eeprom_update_word((uint16_t *)EEPROM_MMU_LOAD_FAIL_TOT, 0);
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_MMU_FAIL) == 0xff) eeprom_update_byte((uint8_t *)EEPROM_MMU_FAIL, 0);
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_MMU_LOAD_FAIL) == 0xff) eeprom_update_byte((uint8_t *)EEPROM_MMU_LOAD_FAIL, 0);
|
||||
if (eeprom_read_byte(&(EEPROM_Sheets_base->active_sheet)) == 0xff) eeprom_update_byte(&(EEPROM_Sheets_base->active_sheet), 0);
|
||||
if (eeprom_read_byte(&(EEPROM_Sheets_base->active_sheet)) == EEPROM_EMPTY_VALUE)
|
||||
{
|
||||
eeprom_update_byte(&(EEPROM_Sheets_base->active_sheet), 0);
|
||||
// When upgrading from version older version (before multiple sheets were implemented in v3.8.0)
|
||||
// Sheet 1 uses the previous Live adjust Z (@EEPROM_BABYSTEP_Z)
|
||||
int last_babystep = eeprom_read_word((uint16_t *)EEPROM_BABYSTEP_Z);
|
||||
eeprom_update_word(reinterpret_cast<uint16_t *>(&(EEPROM_Sheets_base->s[0].z_offset)), last_babystep);
|
||||
}
|
||||
|
||||
for (uint_least8_t i = 0; i < (sizeof(Sheets::s)/sizeof(Sheets::s[0])); ++i)
|
||||
{
|
||||
@ -72,24 +80,108 @@ void eeprom_init()
|
||||
}
|
||||
if(is_uninitialized)
|
||||
{
|
||||
SheetName sheetName;
|
||||
eeprom_default_sheet_name(i,sheetName);
|
||||
|
||||
char sheet_PROGMEM_buffer[8];
|
||||
strcpy_P(sheet_PROGMEM_buffer, (char *)pgm_read_word(&(defaultSheetNames[i])));
|
||||
for (uint_least8_t a = 0; a < sizeof(Sheet::name); ++a){
|
||||
eeprom_write(&(EEPROM_Sheets_base->s[i].name[a]), sheet_PROGMEM_buffer[a]);
|
||||
}
|
||||
|
||||
// When upgrading from version older version (before multiple sheets were implemented in v3.8.0)
|
||||
// Sheet 1 uses the previous Live adjust Z (@EEPROM_BABYSTEP_Z)
|
||||
if(i == 0){
|
||||
int last_babystep = eeprom_read_word((uint16_t *)EEPROM_BABYSTEP_Z);
|
||||
eeprom_write_word(reinterpret_cast<uint16_t *>(&(EEPROM_Sheets_base->s[i].z_offset)), last_babystep);
|
||||
eeprom_write(&(EEPROM_Sheets_base->s[i].name[a]), sheetName.c[a]);
|
||||
}
|
||||
}
|
||||
}
|
||||
if(!eeprom_is_sheet_initialized(eeprom_read_byte(&(EEPROM_Sheets_base->active_sheet))))
|
||||
{
|
||||
eeprom_switch_to_next_sheet();
|
||||
}
|
||||
check_babystep();
|
||||
}
|
||||
|
||||
//! @brief Get default sheet name for index
|
||||
//!
|
||||
//! | index | sheetName |
|
||||
//! | ----- | --------- |
|
||||
//! | 0 | Smooth1 |
|
||||
//! | 1 | Smooth2 |
|
||||
//! | 2 | Textur1 |
|
||||
//! | 3 | Textur2 |
|
||||
//! | 4 | Custom1 |
|
||||
//! | 5 | Custom2 |
|
||||
//! | 6 | Custom3 |
|
||||
//! | 7 | Custom4 |
|
||||
//!
|
||||
//! @param[in] index
|
||||
//! @param[out] sheetName
|
||||
void eeprom_default_sheet_name(uint8_t index, SheetName &sheetName)
|
||||
{
|
||||
static_assert(8 == sizeof(SheetName),"Default sheet name needs to be adjusted.");
|
||||
|
||||
if (index < 2)
|
||||
{
|
||||
strcpy_P(sheetName.c, PSTR("Smooth"));
|
||||
}
|
||||
else if (index < 4)
|
||||
{
|
||||
strcpy_P(sheetName.c, PSTR("Textur"));
|
||||
}
|
||||
else
|
||||
{
|
||||
strcpy_P(sheetName.c, PSTR("Custom"));
|
||||
}
|
||||
|
||||
switch (index)
|
||||
{
|
||||
case 0:
|
||||
sheetName.c[6] = '1';
|
||||
break;
|
||||
case 1:
|
||||
sheetName.c[6] = '2';
|
||||
break;
|
||||
case 2:
|
||||
sheetName.c[6] = '1';
|
||||
break;
|
||||
case 3:
|
||||
sheetName.c[6] = '2';
|
||||
break;
|
||||
case 4:
|
||||
sheetName.c[6] = '1';
|
||||
break;
|
||||
case 5:
|
||||
sheetName.c[6] = '2';
|
||||
break;
|
||||
case 6:
|
||||
sheetName.c[6] = '3';
|
||||
break;
|
||||
case 7:
|
||||
sheetName.c[6] = '4';
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
sheetName.c[7] = '\0';
|
||||
}
|
||||
|
||||
//! @brief Get next initialized sheet
|
||||
//!
|
||||
//! If current sheet is the only sheet initialized, current sheet is returned.
|
||||
//!
|
||||
//! @param sheet Current sheet
|
||||
//! @return next initialized sheet
|
||||
//! @retval -1 no sheet is initialized
|
||||
int8_t eeprom_next_initialized_sheet(int8_t sheet)
|
||||
{
|
||||
for (int8_t i = 0; i < static_cast<int8_t>(sizeof(Sheets::s)/sizeof(Sheet)); ++i)
|
||||
{
|
||||
++sheet;
|
||||
if (sheet >= static_cast<int8_t>(sizeof(Sheets::s)/sizeof(Sheet))) sheet = 0;
|
||||
if (eeprom_is_sheet_initialized(sheet)) return sheet;
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
void eeprom_switch_to_next_sheet()
|
||||
{
|
||||
int8_t sheet = eeprom_read_byte(&(EEPROM_Sheets_base->active_sheet));
|
||||
|
||||
sheet = eeprom_next_initialized_sheet(sheet);
|
||||
if (sheet >= 0) eeprom_update_byte(&(EEPROM_Sheets_base->active_sheet), sheet);
|
||||
}
|
||||
|
@ -3,15 +3,12 @@
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
void eeprom_init();
|
||||
extern bool is_sheet_initialized(uint8_t sheet_num);
|
||||
#endif
|
||||
|
||||
#define MAX_SHEETS 8
|
||||
#define MAX_SHEET_NAME_LENGTH 7
|
||||
|
||||
typedef struct
|
||||
{
|
||||
char name[7]; //!< Can be null terminated, doesn't need to be null terminated
|
||||
char name[MAX_SHEET_NAME_LENGTH]; //!< Can be null terminated, doesn't need to be null terminated
|
||||
int16_t z_offset; //!< Z_BABYSTEP_MIN .. Z_BABYSTEP_MAX = Z_BABYSTEP_MIN*2/1000 [mm] .. Z_BABYSTEP_MAX*2/1000 [mm]
|
||||
uint8_t bed_temp; //!< 0 .. 254 [°C]
|
||||
uint8_t pinda_temp; //!< 0 .. 254 [°C]
|
||||
@ -19,26 +16,27 @@ typedef struct
|
||||
|
||||
typedef struct
|
||||
{
|
||||
Sheet s[3];
|
||||
Sheet s[MAX_SHEETS];
|
||||
uint8_t active_sheet;
|
||||
} Sheets;
|
||||
// sizeof(Sheets). Do not change it unless EEPROM_Sheets_base is last item in EEPROM.
|
||||
// Otherwise it would move following items.
|
||||
#define EEPROM_SHEETS_SIZEOF 34
|
||||
#define EEPROM_SHEETS_SIZEOF 89
|
||||
|
||||
#ifdef __cplusplus
|
||||
static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEPROM_SHEETS_SIZEOF.");
|
||||
#endif
|
||||
|
||||
#define EEPROM_EMPTY_VALUE 0xFF
|
||||
#define EEPROM_EMPTY_VALUE16 0xFFFF
|
||||
// The total size of the EEPROM is
|
||||
// 4096 for the Atmega2560
|
||||
#define EEPROM_TOP 4096
|
||||
#define EEPROM_SILENT 4095
|
||||
#define EEPROM_LANG 4094
|
||||
#define EEPROM_BABYSTEP_X 4092
|
||||
#define EEPROM_BABYSTEP_Y 4090
|
||||
#define EEPROM_BABYSTEP_Z 4088
|
||||
#define EEPROM_BABYSTEP_X 4092 //unused
|
||||
#define EEPROM_BABYSTEP_Y 4090 //unused
|
||||
#define EEPROM_BABYSTEP_Z 4088 //legacy, multiple values stored now in EEPROM_Sheets_base
|
||||
#define EEPROM_CALIBRATION_STATUS 4087
|
||||
#define EEPROM_BABYSTEP_Z0 4085
|
||||
#define EEPROM_FILAMENTUSED 4081
|
||||
@ -76,7 +74,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
#define EEPROM_UVLO_CURRENT_POSITION_Z (EEPROM_FILE_POSITION - 4) //float for current position in Z
|
||||
#define EEPROM_UVLO_TARGET_HOTEND (EEPROM_UVLO_CURRENT_POSITION_Z - 1)
|
||||
#define EEPROM_UVLO_TARGET_BED (EEPROM_UVLO_TARGET_HOTEND - 1)
|
||||
#define EEPROM_UVLO_FEEDRATE (EEPROM_UVLO_TARGET_BED - 2)
|
||||
#define EEPROM_UVLO_FEEDRATE (EEPROM_UVLO_TARGET_BED - 2) //uint16_t
|
||||
#define EEPROM_UVLO_FAN_SPEED (EEPROM_UVLO_FEEDRATE - 1)
|
||||
#define EEPROM_FAN_CHECK_ENABLED (EEPROM_UVLO_FAN_SPEED - 1)
|
||||
#define EEPROM_UVLO_MESH_BED_LEVELING (EEPROM_FAN_CHECK_ENABLED - 9*2)
|
||||
@ -203,9 +201,14 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
#define EEPROM_SHEETS_BASE (EEPROM_CHECK_GCODE - EEPROM_SHEETS_SIZEOF) // Sheets
|
||||
static Sheets * const EEPROM_Sheets_base = (Sheets*)(EEPROM_SHEETS_BASE);
|
||||
|
||||
#define EEPROM_FSENSOR_PCB (EEPROM_SHEETS_BASE-1) // uint8
|
||||
#define EEPROM_FSENSOR_ACTION_NA (EEPROM_FSENSOR_PCB-1) // uint8
|
||||
|
||||
#define EEPROM_UVLO_SAVED_TARGET (EEPROM_FSENSOR_ACTION_NA - 4*4) // 4 x float for saved target for all axes
|
||||
#define EEPROM_UVLO_FEEDMULTIPLY (EEPROM_UVLO_SAVED_TARGET - 2) // uint16_t for feedmultiply
|
||||
|
||||
//This is supposed to point to last item to allow EEPROM overrun check. Please update when adding new items.
|
||||
#define EEPROM_LAST_ITEM EEPROM_SHEETS_BASE
|
||||
#define EEPROM_LAST_ITEM EEPROM_UVLO_FEEDMULTIPLY
|
||||
// !!!!!
|
||||
// !!!!! this is end of EEPROM section ... all updates MUST BE inserted before this mark !!!!!
|
||||
// !!!!!
|
||||
@ -235,5 +238,16 @@ enum
|
||||
EEPROM_MMU_CUTTER_ENABLED_always = 2,
|
||||
};
|
||||
|
||||
#ifdef __cplusplus
|
||||
void eeprom_init();
|
||||
bool eeprom_is_sheet_initialized(uint8_t sheet_num);
|
||||
struct SheetName
|
||||
{
|
||||
char c[sizeof(Sheet::name) + 1];
|
||||
};
|
||||
void eeprom_default_sheet_name(uint8_t index, SheetName &sheetName);
|
||||
int8_t eeprom_next_initialized_sheet(int8_t sheet);
|
||||
void eeprom_switch_to_next_sheet();
|
||||
#endif
|
||||
|
||||
#endif // EEPROM_H
|
||||
|
@ -10,45 +10,52 @@
|
||||
#include "mmu.h"
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
//! @brief Preheat
|
||||
void lay1cal_preheat()
|
||||
//! @brief Wait for preheat
|
||||
void lay1cal_wait_preheat()
|
||||
{
|
||||
static const char cmd_preheat_0[] PROGMEM = "M107";
|
||||
static const char cmd_preheat_1[] PROGMEM = "M104 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP);
|
||||
static const char cmd_preheat_2[] PROGMEM = "M140 S" STRINGIFY(PLA_PREHEAT_HPB_TEMP);
|
||||
static const char cmd_preheat_3[] PROGMEM = "M190 S" STRINGIFY(PLA_PREHEAT_HPB_TEMP);
|
||||
static const char cmd_preheat_4[] PROGMEM = "M109 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP);
|
||||
static const char cmd_preheat_5[] PROGMEM = "G28";
|
||||
static const char cmd_preheat_6[] PROGMEM = "G92 E0.0";
|
||||
static const char cmd_preheat_1[] PROGMEM = "M190";
|
||||
static const char cmd_preheat_2[] PROGMEM = "M109";
|
||||
static const char cmd_preheat_4[] PROGMEM = "G28";
|
||||
static const char cmd_preheat_5[] PROGMEM = "G92 E0.0";
|
||||
|
||||
static const char * const preheat_cmd[] PROGMEM =
|
||||
const char * const preheat_cmd[] =
|
||||
{
|
||||
cmd_preheat_0,
|
||||
cmd_preheat_1,
|
||||
cmd_preheat_2,
|
||||
cmd_preheat_3,
|
||||
_T(MSG_M117_V2_CALIBRATION),
|
||||
cmd_preheat_4,
|
||||
cmd_preheat_5, //call MSG_M117_V2_CALIBRATION before
|
||||
cmd_preheat_6,
|
||||
cmd_preheat_5,
|
||||
};
|
||||
|
||||
for (uint8_t i = 0; i < (sizeof(preheat_cmd)/sizeof(preheat_cmd[0])); ++i)
|
||||
{
|
||||
if (5 == i) enquecommand_P(_T(MSG_M117_V2_CALIBRATION));
|
||||
enquecommand_P(static_cast<char*>(pgm_read_ptr(&preheat_cmd[i])));
|
||||
enquecommand_P(preheat_cmd[i]);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//! @brief Load filament
|
||||
//! @param cmd_buffer character buffer needed to format gcodes
|
||||
//! @param filament filament to use (applies for MMU only)
|
||||
void lay1cal_load_filament(char *cmd_buffer, uint8_t filament)
|
||||
{
|
||||
if (mmu_enabled)
|
||||
{
|
||||
enquecommand_P(PSTR("M83"));
|
||||
enquecommand_P(PSTR("G1 Y-3.0 F1000.0"));
|
||||
enquecommand_P(PSTR("G1 Z0.4 F1000.0"));
|
||||
sprintf_P(cmd_buffer, PSTR("T%d"), filament);
|
||||
enquecommand(cmd_buffer);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//! @brief Print intro line
|
||||
//! @param cmd_buffer character buffer needed to format gcodes
|
||||
//! @param filament filament to use (applies for MMU only)
|
||||
void lay1cal_intro_line(char *cmd_buffer, uint8_t filament)
|
||||
void lay1cal_intro_line()
|
||||
{
|
||||
static const char cmd_intro_mmu_0[] PROGMEM = "M83";
|
||||
static const char cmd_intro_mmu_1[] PROGMEM = "G1 Y-3.0 F1000.0";
|
||||
static const char cmd_intro_mmu_2[] PROGMEM = "G1 Z0.4 F1000.0";
|
||||
static const char cmd_intro_mmu_3[] PROGMEM = "G1 X55.0 E32.0 F1073.0"; // call T code before
|
||||
static const char cmd_intro_mmu_3[] PROGMEM = "G1 X55.0 E32.0 F1073.0";
|
||||
static const char cmd_intro_mmu_4[] PROGMEM = "G1 X5.0 E32.0 F1800.0";
|
||||
static const char cmd_intro_mmu_5[] PROGMEM = "G1 X55.0 E8.0 F2000.0";
|
||||
static const char cmd_intro_mmu_6[] PROGMEM = "G1 Z0.3 F1000.0";
|
||||
@ -61,10 +68,7 @@ void lay1cal_intro_line(char *cmd_buffer, uint8_t filament)
|
||||
|
||||
static const char * const intro_mmu_cmd[] PROGMEM =
|
||||
{
|
||||
cmd_intro_mmu_0,
|
||||
cmd_intro_mmu_1,
|
||||
cmd_intro_mmu_2,
|
||||
cmd_intro_mmu_3, // call T code before
|
||||
cmd_intro_mmu_3,
|
||||
cmd_intro_mmu_4,
|
||||
cmd_intro_mmu_5,
|
||||
cmd_intro_mmu_6,
|
||||
@ -80,11 +84,6 @@ void lay1cal_intro_line(char *cmd_buffer, uint8_t filament)
|
||||
{
|
||||
for (uint8_t i = 0; i < (sizeof(intro_mmu_cmd)/sizeof(intro_mmu_cmd[0])); ++i)
|
||||
{
|
||||
if (3 == i)
|
||||
{
|
||||
sprintf_P(cmd_buffer, PSTR("T%d"), filament);
|
||||
enquecommand(cmd_buffer);
|
||||
}
|
||||
enquecommand_P(static_cast<char*>(pgm_read_ptr(&intro_mmu_cmd[i])));
|
||||
}
|
||||
}
|
||||
|
@ -6,8 +6,9 @@
|
||||
#define FIRMWARE_FIRST_LAY_CAL_H_
|
||||
#include <stdint.h>
|
||||
|
||||
void lay1cal_preheat();
|
||||
void lay1cal_intro_line(char *cmd_buffer, uint8_t filament);
|
||||
void lay1cal_wait_preheat();
|
||||
void lay1cal_load_filament(char *cmd_buffer, uint8_t filament);
|
||||
void lay1cal_intro_line();
|
||||
void lay1cal_before_meander();
|
||||
void lay1cal_meander(char *cmd_buffer);
|
||||
void lay1cal_square(char *cmd_buffer, uint8_t i);
|
||||
|
@ -15,6 +15,10 @@
|
||||
#include "mmu.h"
|
||||
#include "cardreader.h"
|
||||
|
||||
#include "adc.h"
|
||||
#include "temperature.h"
|
||||
#include "config.h"
|
||||
|
||||
//! @name Basic parameters
|
||||
//! @{
|
||||
#define FSENSOR_CHUNK_LEN 0.64F //!< filament sensor chunk length 0.64mm
|
||||
@ -53,15 +57,8 @@ bool fsensor_enabled = true;
|
||||
bool fsensor_watch_runout = true;
|
||||
//! not responding - is set if any communication error occurred during initialization or readout
|
||||
bool fsensor_not_responding = false;
|
||||
//! printing saved
|
||||
bool fsensor_printing_saved = false;
|
||||
//! enable/disable quality meassurement
|
||||
bool fsensor_oq_meassure_enabled = false;
|
||||
//! as explained in the CHECK_FSENSOR macro: this flag is set to true when fsensor posts
|
||||
//! the M600 into the command queue, which elliminates the hazard of having posted multiple M600's
|
||||
//! before the first one gets read and started processing.
|
||||
//! Btw., the IR fsensor could do up to 6 posts before the command queue managed to start processing the first M600 ;)
|
||||
static bool fsensor_m600_enqueued = false;
|
||||
|
||||
//! number of errors, updated in ISR
|
||||
uint8_t fsensor_err_cnt = 0;
|
||||
@ -117,6 +114,13 @@ int16_t fsensor_oq_yd_max;
|
||||
uint16_t fsensor_oq_sh_sum;
|
||||
//! @}
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
ClFsensorPCB oFsensorPCB;
|
||||
ClFsensorActionNA oFsensorActionNA;
|
||||
bool bIRsensorStateFlag=false;
|
||||
unsigned long nIRsensorLastTime;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
void fsensor_stop_and_save_print(void)
|
||||
{
|
||||
printf_P(PSTR("fsensor_stop_and_save_print\n"));
|
||||
@ -126,20 +130,28 @@ void fsensor_stop_and_save_print(void)
|
||||
void fsensor_restore_print_and_continue(void)
|
||||
{
|
||||
printf_P(PSTR("fsensor_restore_print_and_continue\n"));
|
||||
fsensor_watch_runout = true;
|
||||
fsensor_err_cnt = 0;
|
||||
fsensor_m600_enqueued = false;
|
||||
restore_print_from_ram_and_continue(0); //XYZ = orig, E - no change
|
||||
}
|
||||
|
||||
// fsensor_checkpoint_print cuts the current print job at the current position,
|
||||
// allowing new instructions to be inserted in the middle
|
||||
void fsensor_checkpoint_print(void)
|
||||
{
|
||||
printf_P(PSTR("fsensor_checkpoint_print\n"));
|
||||
stop_and_save_print_to_ram(0, 0);
|
||||
restore_print_from_ram_and_continue(0);
|
||||
}
|
||||
|
||||
void fsensor_init(void)
|
||||
{
|
||||
#ifdef PAT9125
|
||||
uint8_t pat9125 = pat9125_init();
|
||||
printf_P(PSTR("PAT9125_init:%hhu\n"), pat9125);
|
||||
printf_P(PSTR("PAT9125_init:%hhu\n"), pat9125);
|
||||
#endif //PAT9125
|
||||
uint8_t fsensor = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR);
|
||||
fsensor_autoload_enabled=eeprom_read_byte((uint8_t*)EEPROM_FSENS_AUTOLOAD_ENABLED);
|
||||
fsensor_not_responding = false;
|
||||
#ifdef PAT9125
|
||||
uint8_t oq_meassure_enabled = eeprom_read_byte((uint8_t*)EEPROM_FSENS_OQ_MEASS_ENABLED);
|
||||
fsensor_oq_meassure_enabled = (oq_meassure_enabled == 1)?true:false;
|
||||
@ -150,19 +162,27 @@ void fsensor_init(void)
|
||||
fsensor = 0; //disable sensor
|
||||
fsensor_not_responding = true;
|
||||
}
|
||||
else
|
||||
fsensor_not_responding = false;
|
||||
#endif //PAT9125
|
||||
#if IR_SENSOR_ANALOG
|
||||
bIRsensorStateFlag=false;
|
||||
oFsensorPCB=(ClFsensorPCB)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_PCB);
|
||||
oFsensorActionNA=(ClFsensorActionNA)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_ACTION_NA);
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
if (fsensor)
|
||||
fsensor_enable();
|
||||
fsensor_enable(false); // (in this case) EEPROM update is not necessary
|
||||
else
|
||||
fsensor_disable();
|
||||
printf_P(PSTR("FSensor %S\n"), (fsensor_enabled?PSTR("ENABLED"):PSTR("DISABLED\n")));
|
||||
fsensor_disable(false); // (in this case) EEPROM update is not necessary
|
||||
printf_P(PSTR("FSensor %S"), (fsensor_enabled?PSTR("ENABLED"):PSTR("DISABLED")));
|
||||
#if IR_SENSOR_ANALOG
|
||||
printf_P(PSTR(" (sensor board revision: %S)\n"),(oFsensorPCB==ClFsensorPCB::_Rev03b)?PSTR("03b or newer"):PSTR("03 or older"));
|
||||
#else //IR_SENSOR_ANALOG
|
||||
printf_P(PSTR("\n"));
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
if (check_for_ir_sensor()) ir_sensor_detected = true;
|
||||
|
||||
}
|
||||
|
||||
bool fsensor_enable(void)
|
||||
bool fsensor_enable(bool bUpdateEEPROM)
|
||||
{
|
||||
#ifdef PAT9125
|
||||
if (mmu_enabled == false) { //filament sensor is pat9125, enable only if it is working
|
||||
@ -187,18 +207,34 @@ bool fsensor_enable(void)
|
||||
FSensorStateMenu = 1;
|
||||
}
|
||||
#else // PAT9125
|
||||
fsensor_enabled = true;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0x01);
|
||||
FSensorStateMenu = 1;
|
||||
#endif // PAT9125
|
||||
#if IR_SENSOR_ANALOG
|
||||
if(!fsensor_IR_check())
|
||||
{
|
||||
bUpdateEEPROM=true;
|
||||
fsensor_enabled=false;
|
||||
fsensor_not_responding=true;
|
||||
FSensorStateMenu=0;
|
||||
}
|
||||
else {
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
fsensor_enabled=true;
|
||||
fsensor_not_responding=false;
|
||||
FSensorStateMenu=1;
|
||||
#if IR_SENSOR_ANALOG
|
||||
}
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
if(bUpdateEEPROM)
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, FSensorStateMenu);
|
||||
#endif //PAT9125
|
||||
return fsensor_enabled;
|
||||
}
|
||||
|
||||
void fsensor_disable(void)
|
||||
{
|
||||
void fsensor_disable(bool bUpdateEEPROM)
|
||||
{
|
||||
fsensor_enabled = false;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0x00);
|
||||
FSensorStateMenu = 0;
|
||||
if(bUpdateEEPROM)
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, 0x00);
|
||||
}
|
||||
|
||||
void fsensor_autoload_set(bool State)
|
||||
@ -529,8 +565,6 @@ void fsensor_enque_M600(){
|
||||
printf_P(PSTR("fsensor_update - M600\n"));
|
||||
eeprom_update_byte((uint8_t*)EEPROM_FERROR_COUNT, eeprom_read_byte((uint8_t*)EEPROM_FERROR_COUNT) + 1);
|
||||
eeprom_update_word((uint16_t*)EEPROM_FERROR_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_FERROR_COUNT_TOT) + 1);
|
||||
enquecommand_front_P(PSTR("PRUSA fsensor_recover"));
|
||||
fsensor_m600_enqueued = true;
|
||||
enquecommand_front_P((PSTR("M600")));
|
||||
}
|
||||
|
||||
@ -542,7 +576,7 @@ void fsensor_enque_M600(){
|
||||
void fsensor_update(void)
|
||||
{
|
||||
#ifdef PAT9125
|
||||
if (fsensor_enabled && fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX) && ( ! fsensor_m600_enqueued) )
|
||||
if (fsensor_enabled && fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX))
|
||||
{
|
||||
bool autoload_enabled_tmp = fsensor_autoload_enabled;
|
||||
fsensor_autoload_enabled = false;
|
||||
@ -575,24 +609,86 @@ void fsensor_update(void)
|
||||
err |= (fsensor_oq_er_sum > 2);
|
||||
err |= (fsensor_oq_yd_sum < (4 * FSENSOR_OQ_MIN_YD));
|
||||
|
||||
if (!err)
|
||||
{
|
||||
printf_P(PSTR("fsensor_err_cnt = 0\n"));
|
||||
fsensor_restore_print_and_continue();
|
||||
}
|
||||
else
|
||||
{
|
||||
fsensor_enque_M600();
|
||||
fsensor_watch_runout = false;
|
||||
}
|
||||
fsensor_restore_print_and_continue();
|
||||
fsensor_autoload_enabled = autoload_enabled_tmp;
|
||||
fsensor_oq_meassure_enabled = oq_meassure_enabled_tmp;
|
||||
|
||||
if (!err)
|
||||
printf_P(PSTR("fsensor_err_cnt = 0\n"));
|
||||
else
|
||||
fsensor_enque_M600();
|
||||
}
|
||||
#else //PAT9125
|
||||
if ((digitalRead(IR_SENSOR_PIN) == 1) && CHECK_FSENSOR && fsensor_enabled && ir_sensor_detected && ( ! fsensor_m600_enqueued) )
|
||||
{
|
||||
fsensor_stop_and_save_print();
|
||||
fsensor_enque_M600();
|
||||
if (CHECK_FSENSOR && fsensor_enabled && ir_sensor_detected)
|
||||
{
|
||||
if(digitalRead(IR_SENSOR_PIN))
|
||||
{ // IR_SENSOR_PIN ~ H
|
||||
#if IR_SENSOR_ANALOG
|
||||
if(!bIRsensorStateFlag)
|
||||
{
|
||||
bIRsensorStateFlag=true;
|
||||
nIRsensorLastTime=_millis();
|
||||
}
|
||||
else
|
||||
{
|
||||
if((_millis()-nIRsensorLastTime)>IR_SENSOR_STEADY)
|
||||
{
|
||||
uint8_t nMUX1,nMUX2;
|
||||
uint16_t nADC;
|
||||
bIRsensorStateFlag=false;
|
||||
// sequence for direct data reading from AD converter
|
||||
DISABLE_TEMPERATURE_INTERRUPT();
|
||||
nMUX1=ADMUX; // ADMUX saving
|
||||
nMUX2=ADCSRB;
|
||||
adc_setmux(VOLT_IR_PIN);
|
||||
ADCSRA|=(1<<ADSC); // first conversion after ADMUX change discarded (preventively)
|
||||
while(ADCSRA&(1<<ADSC))
|
||||
;
|
||||
ADCSRA|=(1<<ADSC); // second conversion used
|
||||
while(ADCSRA&(1<<ADSC))
|
||||
;
|
||||
nADC=ADC;
|
||||
ADMUX=nMUX1; // ADMUX restoring
|
||||
ADCSRB=nMUX2;
|
||||
ENABLE_TEMPERATURE_INTERRUPT();
|
||||
// end of sequence for ...
|
||||
if((oFsensorPCB==ClFsensorPCB::_Rev03b)&&((nADC*OVERSAMPLENR)>((int)IRsensor_Hopen_TRESHOLD)))
|
||||
{
|
||||
fsensor_disable();
|
||||
fsensor_not_responding = true;
|
||||
printf_P(PSTR("IR sensor not responding (%d)!\n"),1);
|
||||
if((ClFsensorActionNA)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_ACTION_NA)==ClFsensorActionNA::_Pause)
|
||||
if(oFsensorActionNA==ClFsensorActionNA::_Pause)
|
||||
lcd_pause_print();
|
||||
}
|
||||
else
|
||||
{
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
fsensor_checkpoint_print();
|
||||
fsensor_enque_M600();
|
||||
#if IR_SENSOR_ANALOG
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{ // IR_SENSOR_PIN ~ L
|
||||
bIRsensorStateFlag=false;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
}
|
||||
}
|
||||
#endif //PAT9125
|
||||
}
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
bool fsensor_IR_check()
|
||||
{
|
||||
uint16_t volt_IR_int;
|
||||
bool bCheckResult;
|
||||
|
||||
volt_IR_int=current_voltage_raw_IR;
|
||||
bCheckResult=(volt_IR_int<((int)IRsensor_Lmax_TRESHOLD))||(volt_IR_int>((int)IRsensor_Hmin_TRESHOLD));
|
||||
bCheckResult=bCheckResult&&(!((oFsensorPCB==ClFsensorPCB::_Rev03b)&&(volt_IR_int>((int)IRsensor_Hopen_TRESHOLD))));
|
||||
return(bCheckResult);
|
||||
}
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
@ -3,6 +3,7 @@
|
||||
#define FSENSOR_H
|
||||
|
||||
#include <inttypes.h>
|
||||
#include "config.h"
|
||||
|
||||
|
||||
//! minimum meassured chunk length in steps
|
||||
@ -20,6 +21,8 @@ extern bool fsensor_oq_meassure_enabled;
|
||||
extern void fsensor_stop_and_save_print(void);
|
||||
//! restore print - restore position and heatup to original temperature
|
||||
extern void fsensor_restore_print_and_continue(void);
|
||||
//! split the current gcode stream to insert new instructions
|
||||
extern void fsensor_checkpoint_print(void);
|
||||
//! @}
|
||||
|
||||
//! initialize
|
||||
@ -27,8 +30,8 @@ extern void fsensor_init(void);
|
||||
|
||||
//! @name enable/disable
|
||||
//! @{
|
||||
extern bool fsensor_enable(void);
|
||||
extern void fsensor_disable(void);
|
||||
extern bool fsensor_enable(bool bUpdateEEPROM=true);
|
||||
extern void fsensor_disable(bool bUpdateEEPROM=true);
|
||||
//! @}
|
||||
|
||||
//autoload feature enabled
|
||||
@ -65,4 +68,28 @@ extern void fsensor_st_block_begin(block_t* bl);
|
||||
extern void fsensor_st_block_chunk(block_t* bl, int cnt);
|
||||
//! @}
|
||||
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
#define IR_SENSOR_STEADY 10 // [ms]
|
||||
|
||||
enum class ClFsensorPCB:uint_least8_t
|
||||
{
|
||||
_Old=0,
|
||||
_Rev03b=1,
|
||||
_Undef=EEPROM_EMPTY_VALUE
|
||||
};
|
||||
|
||||
enum class ClFsensorActionNA:uint_least8_t
|
||||
{
|
||||
_Continue=0,
|
||||
_Pause=1,
|
||||
_Undef=EEPROM_EMPTY_VALUE
|
||||
};
|
||||
|
||||
extern ClFsensorPCB oFsensorPCB;
|
||||
extern ClFsensorActionNA oFsensorActionNA;
|
||||
|
||||
extern bool fsensor_IR_check();
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
#endif //FSENSOR_H
|
||||
|
@ -19,91 +19,162 @@
|
||||
// So the automaton runs atop of inner 8 (or 16) cycles.
|
||||
// The finite automaton is running in the ISR(TIMER0_OVF_vect)
|
||||
|
||||
// 2019-08-14 update: the original algorithm worked very well, however there were 2 regressions:
|
||||
// 1. 62kHz ISR requires considerable amount of processing power,
|
||||
// USB transfer speed dropped by 20%, which was most notable when doing short G-code segments.
|
||||
// 2. Some users reported TLed PSU started clicking when running at 120V/60Hz.
|
||||
// This looks like the original algorithm didn't maintain base PWM 30Hz, but only 15Hz
|
||||
// To address both issues, there is an improved approach based on the idea of leveraging
|
||||
// different CLK prescalers in some automaton states - i.e. when holding LOW or HIGH on the output pin,
|
||||
// we don't have to clock 62kHz, but we can increase the CLK prescaler for these states to 8 (or even 64).
|
||||
// That shall result in the ISR not being called that much resulting in regained performance
|
||||
// Theoretically this is relatively easy, however one must be very carefull handling the AVR's timer
|
||||
// control registers correctly, especially setting them in a correct order.
|
||||
// Some registers are double buffered, some changes are applied in next cycles etc.
|
||||
// The biggest problem was with the CLK prescaler itself - this circuit is shared among almost all timers,
|
||||
// we don't want to reset the prescaler counted value when transiting among automaton states.
|
||||
// Resetting the prescaler would make the PWM more precise, right now there are temporal segments
|
||||
// of variable period ranging from 0 to 7 62kHz ticks - that's logical, the timer must "sync"
|
||||
// to the new slower CLK after setting the slower prescaler value.
|
||||
// In our application, this isn't any significant problem and may be ignored.
|
||||
// Doing changes in timer's registers non-correctly results in artefacts on the output pin
|
||||
// - it can toggle unnoticed, which will result in bed clicking again.
|
||||
// That's why there are special transition states ZERO_TO_RISE and ONE_TO_FALL, which enable the
|
||||
// counter change its operation atomically and without artefacts on the output pin.
|
||||
// The resulting signal on the output pin was checked with an osciloscope.
|
||||
// If there are any change requirements in the future, the signal must be checked with an osciloscope again,
|
||||
// ad-hoc changes may completely screw things up!
|
||||
|
||||
///! Definition off finite automaton states
|
||||
enum class States : uint8_t {
|
||||
ZERO = 0,
|
||||
RISE = 1,
|
||||
ONE = 2,
|
||||
FALL = 3
|
||||
};
|
||||
|
||||
///! State table for the inner part of the finite automaton
|
||||
///! Basically it specifies what shall happen if the outer automaton is requesting setting the heat pin to 0 (OFF) or 1 (ON)
|
||||
///! ZERO: steady 0 (OFF), no change for the whole period
|
||||
///! RISE: 8 (16) fast PWM cycles with increasing duty up to steady ON
|
||||
///! ONE: steady 1 (ON), no change for the whole period
|
||||
///! FALL: 8 (16) fast PWM cycles with decreasing duty down to steady OFF
|
||||
///! @@TODO move it into progmem
|
||||
static States stateTable[4*2] = {
|
||||
// off on
|
||||
States::ZERO, States::RISE, // ZERO
|
||||
States::FALL, States::ONE, // RISE
|
||||
States::FALL, States::ONE, // ONE
|
||||
States::ZERO, States::RISE // FALL
|
||||
ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle
|
||||
ZERO, ///< steady 0 (OFF), no change for the whole period
|
||||
ZERO_TO_RISE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
RISE, ///< 16 fast PWM cycles with increasing duty up to steady ON
|
||||
RISE_TO_ONE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
ONE, ///< steady 1 (ON), no change for the whole period
|
||||
ONE_TO_FALL, ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
FALL, ///< 16 fast PWM cycles with decreasing duty down to steady OFF
|
||||
FALL_TO_ZERO ///< metastate allowing the timer change its state atomically without artefacts on the output pin
|
||||
};
|
||||
|
||||
///! Inner states of the finite automaton
|
||||
static States state = States::ZERO;
|
||||
static States state = States::ZERO_START;
|
||||
|
||||
///! Inner and outer PWM counters
|
||||
static uint8_t outer = 0;
|
||||
static uint8_t inner = 0;
|
||||
///! Fast PWM counter is used in the RISE and FALL states (62.5kHz)
|
||||
static uint8_t slowCounter = 0;
|
||||
///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64)
|
||||
static uint8_t fastCounter = 0;
|
||||
///! PWM counter for the whole cycle - a cache for soft_pwm_bed
|
||||
static uint8_t pwm = 0;
|
||||
|
||||
///! the slow PWM duty for the next 30Hz cycle
|
||||
///! The slow PWM duty for the next 30Hz cycle
|
||||
///! Set in the whole firmware at various places
|
||||
extern unsigned char soft_pwm_bed;
|
||||
|
||||
/// Fine tuning of automaton cycles
|
||||
#if 1
|
||||
static const uint8_t innerMax = 16;
|
||||
static const uint8_t innerShift = 4;
|
||||
#else
|
||||
static const uint8_t innerMax = 8;
|
||||
static const uint8_t innerShift = 5;
|
||||
#endif
|
||||
/// fastMax - how many fast PWM steps to do in RISE and FALL states
|
||||
/// 16 is a good compromise between silenced bed ("smooth" edges)
|
||||
/// and not burning the switching MOSFET
|
||||
static const uint8_t fastMax = 16;
|
||||
|
||||
/// Scaler 16->256 for fast PWM
|
||||
static const uint8_t fastShift = 4;
|
||||
|
||||
/// Increment slow PWM counter by slowInc every ZERO or ONE state
|
||||
/// This allows for fine-tuning the basic PWM switching frequency
|
||||
/// A possible further optimization - use a 64 prescaler (instead of 8)
|
||||
/// increment slowCounter by 1
|
||||
/// but use less bits of soft PWM - something like soft_pwm_bed >> 2
|
||||
/// that may further reduce the CPU cycles required by the bed heating automaton
|
||||
/// Due to the nature of bed heating the reduced PID precision may not be a major issue, however doing 8x less ISR(timer0_ovf) may significantly improve the performance
|
||||
static const uint8_t slowInc = 1;
|
||||
|
||||
ISR(TIMER0_OVF_vect) // timer compare interrupt service routine
|
||||
{
|
||||
if( inner ){
|
||||
switch(state){
|
||||
case States::ZERO:
|
||||
OCR0B = 255;
|
||||
// Commenting the following code saves 6B, but it is left here for reference
|
||||
// It is not necessary to set it all over again, because we can only get into the ZERO state from the FALL state (which sets this register)
|
||||
// TCCR0A |= (1 << COM0B1) | (1 << COM0B0);
|
||||
break;
|
||||
case States::RISE:
|
||||
OCR0B = (innerMax - inner) << innerShift;
|
||||
// TCCR0A |= (1 << COM0B1); // this bit is always 1
|
||||
TCCR0A &= ~(1 << COM0B0);
|
||||
break;
|
||||
case States::ONE:
|
||||
OCR0B = 255;
|
||||
// again - may be skipped, because we get into the ONE state only from RISE (which sets this register)
|
||||
// TCCR0A |= (1 << COM0B1);
|
||||
TCCR0A &= ~(1 << COM0B0);
|
||||
break;
|
||||
case States::FALL:
|
||||
OCR0B = (innerMax - inner) << innerShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode
|
||||
// must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle
|
||||
TCCR0A |= /*(1 << COM0B1) |*/ (1 << COM0B0);
|
||||
break;
|
||||
switch(state){
|
||||
case States::ZERO_START:
|
||||
pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit!
|
||||
if( pwm != 0 ){
|
||||
state = States::ZERO; // do nothing, let it tick once again after the 30Hz period
|
||||
}
|
||||
break;
|
||||
case States::ZERO: // end of state ZERO - we'll either stay in ZERO or change to RISE
|
||||
// In any case update our cache of pwm value for the next whole cycle from soft_pwm_bed
|
||||
slowCounter += slowInc; // this does software timer_clk/256 or less (depends on slowInc)
|
||||
if( slowCounter > pwm ){
|
||||
return;
|
||||
} // otherwise moving towards RISE
|
||||
state = States::ZERO_TO_RISE; // and finalize the change in a transitional state RISE0
|
||||
break;
|
||||
// even though it may look like the ZERO state may be glued together with the ZERO_TO_RISE, don't do it
|
||||
// the timer must tick once more in order to get rid of occasional output pin toggles.
|
||||
case States::ZERO_TO_RISE: // special state for handling transition between prescalers and switching inverted->non-inverted fast-PWM without toggling the output pin.
|
||||
// It must be done in consequent steps, otherwise the pin will get flipped up and down during one PWM cycle.
|
||||
// Also beware of the correct sequence of the following timer control registers initialization - it really matters!
|
||||
state = States::RISE; // prepare for standard RISE cycles
|
||||
fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
|
||||
TCNT0 = 255; // force overflow on the next clock cycle
|
||||
TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
TCCR0A &= ~(1 << COM0B0); // Clear OC0B on Compare Match, set OC0B at BOTTOM (non-inverting mode)
|
||||
break;
|
||||
case States::RISE:
|
||||
OCR0B = (fastMax - fastCounter) << fastShift;
|
||||
if( fastCounter ){
|
||||
--fastCounter;
|
||||
} else { // end of RISE cycles, changing into state ONE
|
||||
state = States::RISE_TO_ONE;
|
||||
OCR0B = 255; // full duty
|
||||
TCNT0 = 254; // make the timer overflow in the next cycle
|
||||
// @@TODO these constants are still subject to investigation
|
||||
}
|
||||
break;
|
||||
case States::RISE_TO_ONE:
|
||||
state = States::ONE;
|
||||
OCR0B = 255; // full duty
|
||||
TCNT0 = 255; // make the timer overflow in the next cycle
|
||||
TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
|
||||
break;
|
||||
case States::ONE: // state ONE - we'll either stay in ONE or change to FALL
|
||||
OCR0B = 255;
|
||||
slowCounter += slowInc; // this does software timer_clk/256 or less
|
||||
if( slowCounter < pwm ){
|
||||
return;
|
||||
}
|
||||
if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain
|
||||
// if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating
|
||||
return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf
|
||||
}
|
||||
// otherwise moving towards FALL
|
||||
// @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all
|
||||
state = States::ONE;//_TO_FALL;
|
||||
// TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
// break;
|
||||
// case States::ONE_TO_FALL:
|
||||
// OCR0B = 255; // zero duty
|
||||
state=States::FALL;
|
||||
fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
|
||||
TCNT0 = 255; // force overflow on the next clock cycle
|
||||
TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz
|
||||
// must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle
|
||||
// COM0B1 remains set both in inverting and non-inverting mode
|
||||
TCCR0A |= (1 << COM0B0); // inverting mode
|
||||
break;
|
||||
case States::FALL:
|
||||
OCR0B = (fastMax - fastCounter) << fastShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode
|
||||
//TCCR0A |= (1 << COM0B0); // already set in ONE_TO_FALL
|
||||
if( fastCounter ){
|
||||
--fastCounter;
|
||||
} else { // end of FALL cycles, changing into state ZERO
|
||||
state = States::FALL_TO_ZERO;
|
||||
TCNT0 = 128; //@@TODO again - need to wait long enough to propagate the timer state changes
|
||||
OCR0B = 255;
|
||||
}
|
||||
break;
|
||||
case States::FALL_TO_ZERO:
|
||||
state = States::ZERO_START; // go to read new soft_pwm_bed value for the next cycle
|
||||
TCNT0 = 128;
|
||||
OCR0B = 255;
|
||||
TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
|
||||
break;
|
||||
}
|
||||
--inner;
|
||||
} else {
|
||||
if( ! outer ){ // at the end of 30Hz PWM period
|
||||
// synchro is not needed (almost), soft_pwm_bed is just 1 byte, 1-byte write instruction is atomic
|
||||
pwm = soft_pwm_bed << 1;
|
||||
}
|
||||
if( pwm > outer || pwm >= 254 ){
|
||||
// soft_pwm_bed has a range of 0-127, that why a <<1 is done here. That also means that we may get only up to 254 which we want to be full-time 1 (ON)
|
||||
state = stateTable[ uint8_t(state) * 2 + 1 ];
|
||||
} else {
|
||||
// switch OFF
|
||||
state = stateTable[ uint8_t(state) * 2 + 0 ];
|
||||
}
|
||||
++outer;
|
||||
inner = innerMax;
|
||||
}
|
||||
}
|
||||
|
@ -189,9 +189,10 @@ static void lcd_begin(uint8_t clear)
|
||||
#endif
|
||||
}
|
||||
|
||||
static void lcd_putchar(char c, FILE *)
|
||||
static int lcd_putchar(char c, FILE *)
|
||||
{
|
||||
lcd_write(c);
|
||||
return 0;
|
||||
}
|
||||
|
||||
void lcd_init(void)
|
||||
@ -760,8 +761,7 @@ void lcd_buttons_update(void)
|
||||
//else if (menu_menu == lcd_move_z) lcd_quick_feedback();
|
||||
//lcd_button_pressed is set back to false via lcd_quick_feedback function
|
||||
}
|
||||
else
|
||||
lcd_long_press_active = 0;
|
||||
lcd_long_press_active = 0;
|
||||
}
|
||||
|
||||
lcd_buttons = newbutton;
|
||||
|
@ -11,7 +11,6 @@
|
||||
extern FILE _lcdout;
|
||||
|
||||
#define lcdout (&_lcdout)
|
||||
extern void lcd_putchar(char c, FILE *stream);
|
||||
|
||||
extern void lcd_init(void);
|
||||
|
||||
|
@ -15,7 +15,7 @@
|
||||
|
||||
extern int32_t lcd_encoder;
|
||||
|
||||
#define MENU_DEPTH_MAX 6
|
||||
#define MENU_DEPTH_MAX 7
|
||||
|
||||
static menu_record_t menu_stack[MENU_DEPTH_MAX];
|
||||
|
||||
@ -184,6 +184,22 @@ static void menu_draw_item_puts_P(char type_char, const char* str)
|
||||
lcd_printf_P(PSTR("%c%-18.18S%c"), menu_selection_mark(), str, type_char);
|
||||
}
|
||||
|
||||
static void menu_draw_toggle_puts_P(const char* str, const char* toggle, const uint8_t settings)
|
||||
{
|
||||
//settings:
|
||||
//xxxxxcba
|
||||
//a = selection mark. If it's set(1), then '>' will be used as the first character on the line. Else leave blank
|
||||
//b = toggle string is from progmem
|
||||
//c = do not set cursor at all. Must be handled externally.
|
||||
char lineStr[LCD_WIDTH + 1];
|
||||
const char eol = (toggle == NULL)?LCD_STR_ARROW_RIGHT[0]:' ';
|
||||
if (toggle == NULL) toggle = _T(MSG_NA);
|
||||
sprintf_P(lineStr, PSTR("%c%-18.18S"), (settings & 0x01)?'>':' ', str);
|
||||
sprintf_P(lineStr + LCD_WIDTH - ((settings & 0x02)?strlen_P(toggle):strlen(toggle)) - 3, (settings & 0x02)?PSTR("[%S]%c"):PSTR("[%s]%c"), toggle, eol);
|
||||
if (!(settings & 0x04)) lcd_set_cursor(0, menu_row);
|
||||
fputs(lineStr, lcdout);
|
||||
}
|
||||
|
||||
//! @brief Format sheet name
|
||||
//!
|
||||
//! @param[in] sheet_E Sheet in EEPROM
|
||||
@ -203,9 +219,13 @@ void menu_format_sheet_E(const Sheet &sheet_E, SheetFormatBuffer &buffer)
|
||||
void menu_format_sheet_select_E(const Sheet &sheet_E, SheetFormatBuffer &buffer)
|
||||
{
|
||||
uint_least8_t index = sprintf_P(buffer.c,PSTR("%-9.9S["), _T(MSG_SHEET));
|
||||
eeprom_read_block(&(buffer.c[index]), sheet_E.name, 7);
|
||||
buffer.c[index + 7] = ']';
|
||||
buffer.c[index + 8] = '\0';
|
||||
eeprom_read_block(&(buffer.c[index]), sheet_E.name, sizeof(sheet_E.name)/sizeof(sheet_E.name[0]));
|
||||
for (const uint_least8_t start = index; static_cast<uint_least8_t>(index - start) < sizeof(sheet_E.name)/sizeof(sheet_E.name[0]); ++index)
|
||||
{
|
||||
if (buffer.c[index] == '\0') break;
|
||||
}
|
||||
buffer.c[index] = ']';
|
||||
buffer.c[index + 1] = '\0';
|
||||
}
|
||||
|
||||
static void menu_draw_item_select_sheet_E(char type_char, const Sheet &sheet)
|
||||
@ -290,14 +310,18 @@ uint8_t menu_item_submenu_E(const Sheet &sheet, menu_func_t submenu)
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t menu_item_submenu_select_sheet_E(const Sheet &sheet, menu_func_t submenu)
|
||||
uint8_t menu_item_function_E(const Sheet &sheet, menu_func_t func)
|
||||
{
|
||||
if (menu_item == menu_line)
|
||||
{
|
||||
if (lcd_draw_update) menu_draw_item_select_sheet_E(LCD_STR_ARROW_RIGHT[0], sheet);
|
||||
if (lcd_draw_update) menu_draw_item_select_sheet_E(' ', sheet);
|
||||
if (menu_clicked && (lcd_encoder == menu_item))
|
||||
{
|
||||
menu_submenu(submenu);
|
||||
menu_clicked = false;
|
||||
lcd_consume_click();
|
||||
lcd_update_enabled = 0;
|
||||
if (func) func();
|
||||
lcd_update_enabled = 1;
|
||||
return menu_item_ret();
|
||||
}
|
||||
}
|
||||
@ -367,6 +391,33 @@ uint8_t menu_item_function_P(const char* str, char number, void (*func)(uint8_t)
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t menu_item_toggle_P(const char* str, const char* toggle, menu_func_t func, const uint8_t settings)
|
||||
{
|
||||
if (menu_item == menu_line)
|
||||
{
|
||||
if (lcd_draw_update) menu_draw_toggle_puts_P(str, toggle, settings | (menu_selection_mark()=='>'));
|
||||
if (menu_clicked && (lcd_encoder == menu_item))
|
||||
{
|
||||
if (toggle == NULL) // print N/A warning message
|
||||
{
|
||||
menu_submenu(func);
|
||||
return menu_item_ret();
|
||||
}
|
||||
else // do the actual toggling
|
||||
{
|
||||
menu_clicked = false;
|
||||
lcd_consume_click();
|
||||
lcd_update_enabled = 0;
|
||||
if (func) func();
|
||||
lcd_update_enabled = 1;
|
||||
return menu_item_ret();
|
||||
}
|
||||
}
|
||||
}
|
||||
menu_item++;
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t menu_item_gcode_P(const char* str, const char* str_gcode)
|
||||
{
|
||||
if (menu_item == menu_line)
|
||||
@ -382,17 +433,12 @@ uint8_t menu_item_gcode_P(const char* str, const char* str_gcode)
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
const char menu_20x_space[] PROGMEM = " ";
|
||||
|
||||
const char menu_fmt_int3[] PROGMEM = "%c%.15S:%s%3d";
|
||||
|
||||
const char menu_fmt_float31[] PROGMEM = "%-12.12S%+8.1f";
|
||||
|
||||
const char menu_fmt_float13[] PROGMEM = "%c%-13.13S%+5.3f";
|
||||
|
||||
const char menu_fmt_float13off[] PROGMEM = "%c%-13.13S%6.6s";
|
||||
|
||||
template<typename T>
|
||||
static void menu_draw_P(char chr, const char* str, int16_t val);
|
||||
|
||||
@ -401,8 +447,8 @@ void menu_draw_P<int16_t*>(char chr, const char* str, int16_t val)
|
||||
{
|
||||
int text_len = strlen_P(str);
|
||||
if (text_len > 15) text_len = 15;
|
||||
char spaces[21];
|
||||
strcpy_P(spaces, menu_20x_space);
|
||||
char spaces[LCD_WIDTH + 1] = {0};
|
||||
memset(spaces,' ', LCD_WIDTH);
|
||||
if (val <= -100) spaces[15 - text_len - 1] = 0;
|
||||
else spaces[15 - text_len] = 0;
|
||||
lcd_printf_P(menu_fmt_int3, chr, str, spaces, val);
|
||||
@ -415,7 +461,7 @@ void menu_draw_P<uint8_t*>(char chr, const char* str, int16_t val)
|
||||
float factor = 1.0f + static_cast<float>(val) / 1000.0f;
|
||||
if (val <= _md->minEditValue)
|
||||
{
|
||||
lcd_printf_P(menu_fmt_float13off, chr, str, " [off]");
|
||||
menu_draw_toggle_puts_P(str, _T(MSG_OFF), 0x04 | 0x02 | (chr=='>'));
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -103,8 +103,8 @@ extern uint8_t menu_item_submenu_P(const char* str, menu_func_t submenu);
|
||||
#define MENU_ITEM_SUBMENU_E(sheet, submenu) do { if (menu_item_submenu_E(sheet, submenu)) return; } while (0)
|
||||
extern uint8_t menu_item_submenu_E(const Sheet &sheet, menu_func_t submenu);
|
||||
|
||||
#define MENU_ITEM_SUBMENU_SELECT_SHEET_E(sheet, submenu) do { if (menu_item_submenu_select_sheet_E(sheet, submenu)) return; } while (0)
|
||||
extern uint8_t menu_item_submenu_select_sheet_E(const Sheet &sheet, menu_func_t submenu);
|
||||
#define MENU_ITEM_FUNCTION_E(sheet, submenu) do { if (menu_item_function_E(sheet, submenu)) return; } while (0)
|
||||
extern uint8_t menu_item_function_E(const Sheet &sheet, menu_func_t func);
|
||||
|
||||
#define MENU_ITEM_BACK_P(str) do { if (menu_item_back_P(str)) return; } while (0)
|
||||
extern uint8_t menu_item_back_P(const char* str);
|
||||
@ -118,6 +118,10 @@ extern uint8_t menu_item_function_P(const char* str, menu_func_t func);
|
||||
#define MENU_ITEM_FUNCTION_NR_P(str, number, func, fn_par) do { if (menu_item_function_P(str, number, func, fn_par)) return; } while (0)
|
||||
extern uint8_t menu_item_function_P(const char* str, char number, void (*func)(uint8_t), uint8_t fn_par);
|
||||
|
||||
#define MENU_ITEM_TOGGLE_P(str, toggle, func) do { if (menu_item_toggle_P(str, toggle, func, 0x02)) return; } while (0)
|
||||
#define MENU_ITEM_TOGGLE(str, toggle, func) do { if (menu_item_toggle_P(str, toggle, func, 0x00)) return; } while (0)
|
||||
extern uint8_t menu_item_toggle_P(const char* str, const char* toggle, menu_func_t func, const uint8_t settings);
|
||||
|
||||
#define MENU_ITEM_GCODE_P(str, str_gcode) do { if (menu_item_gcode_P(str, str_gcode)) return; } while (0)
|
||||
extern uint8_t menu_item_gcode_P(const char* str, const char* str_gcode);
|
||||
|
||||
|
@ -919,7 +919,7 @@ static inline void go_xy(float x, float y, float fr)
|
||||
|
||||
static inline void go_to_current(float fr)
|
||||
{
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], fr, active_extruder);
|
||||
plan_buffer_line_curposXYZE(fr, active_extruder);
|
||||
st_synchronize();
|
||||
}
|
||||
|
||||
@ -2769,7 +2769,7 @@ bool sample_z() {
|
||||
//make space
|
||||
current_position[Z_AXIS] += 150;
|
||||
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););
|
||||
//plan_buffer_line_curposXYZE(feedrate, active_extruder););
|
||||
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_PLACE_STEEL_SHEET));
|
||||
|
||||
|
@ -9,7 +9,6 @@
|
||||
|
||||
//internationalized messages
|
||||
const char MSG_AUTO_HOME[] PROGMEM_I1 = ISTR("Auto home"); ////
|
||||
const char MSG_AUTO_MODE_ON[] PROGMEM_I1 = ISTR("Mode [auto power]"); ////
|
||||
const char MSG_BABYSTEP_Z[] PROGMEM_I1 = ISTR("Live adjust Z"); //// c=18
|
||||
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"); ////
|
||||
@ -22,9 +21,7 @@ const char MSG_CARD_MENU[] PROGMEM_I1 = ISTR("Print from SD"); ////
|
||||
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"); ////
|
||||
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]"); ////
|
||||
const char MSG_CRASHDETECT_OFF[] PROGMEM_I1 = ISTR("Crash det. [off]"); ////
|
||||
const char MSG_CRASHDETECT_ON[] PROGMEM_I1 = ISTR("Crash det. [on]"); ////
|
||||
const char MSG_CRASHDETECT[] PROGMEM_I1 = ISTR("Crash det."); ////
|
||||
const char MSG_ERROR[] PROGMEM_I1 = ISTR("ERROR:"); ////
|
||||
const char MSG_EXTRUDER[] PROGMEM_I1 = ISTR("Extruder"); ////c=17 r=1
|
||||
const char MSG_FILAMENT[] PROGMEM_I1 = ISTR("Filament"); ////c=17 r=1
|
||||
@ -40,9 +37,8 @@ const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE2[] PROGMEM_I1 = ISTR(" of 4"); ////
|
||||
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_FOLLOW_Z_CALIBRATION_FLOW[] PROGMEM_I1 = ISTR("There is still a need to make Z calibration. 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]"); ////
|
||||
const char MSG_FSENSOR_ON[] PROGMEM_I1 = ISTR("Fil. sensor [on]"); ////
|
||||
const char MSG_FSENSOR_AUTOLOAD[] PROGMEM_I1 = ISTR("F. autoload"); ////c=17 r=1
|
||||
const char MSG_FSENSOR[] PROGMEM_I1 = ISTR("Fil. sensor"); ////
|
||||
const char MSG_HEATING[] PROGMEM_I1 = ISTR("Heating"); ////
|
||||
const char MSG_HEATING_COMPLETE[] PROGMEM_I1 = ISTR("Heating done."); ////c=20
|
||||
const char MSG_HOMEYZ[] PROGMEM_I1 = ISTR("Calibrate Z"); ////
|
||||
@ -85,14 +81,16 @@ const char MSG_SELFTEST_FILAMENT_SENSOR[] PROGMEM_I1 = ISTR("Filament sensor");
|
||||
const char MSG_SELFTEST_WIRINGERROR[] PROGMEM_I1 = ISTR("Wiring error"); ////
|
||||
const char MSG_SETTINGS[] PROGMEM_I1 = ISTR("Settings"); ////
|
||||
const char MSG_HW_SETUP[] PROGMEM_I1 = ISTR("HW Setup"); ////
|
||||
const char MSG_SILENT_MODE_OFF[] PROGMEM_I1 = ISTR("Mode [high power]"); ////
|
||||
const char MSG_SILENT_MODE_ON[] PROGMEM_I1 = ISTR("Mode [silent]"); ////
|
||||
const char MSG_STEALTH_MODE_OFF[] PROGMEM_I1 = ISTR("Mode [Normal]"); ////
|
||||
const char MSG_STEALTH_MODE_ON[] PROGMEM_I1 = ISTR("Mode [Stealth]"); ////
|
||||
const char MSG_MODE[] PROGMEM_I1 = ISTR("Mode"); ////
|
||||
const char MSG_HIGH_POWER[] PROGMEM_I1 = ISTR("High power"); ////
|
||||
const char MSG_AUTO_POWER[] PROGMEM_I1 = ISTR("Auto power"); ////
|
||||
const char MSG_SILENT[] PROGMEM_I1 = ISTR("Silent"); ////
|
||||
const char MSG_NORMAL[] PROGMEM_I1 = ISTR("Normal"); ////
|
||||
const char MSG_STEALTH[] PROGMEM_I1 = ISTR("Stealth"); ////
|
||||
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"); ////
|
||||
const char MSG_STOPPED[] PROGMEM_I1 = ISTR("STOPPED. "); ////
|
||||
const char MSG_TEMP_CALIBRATION[] PROGMEM_I1 = ISTR("Temp. cal. "); ////c=20 r=1
|
||||
const char MSG_TEMP_CALIBRATION[] PROGMEM_I1 = ISTR("Temp. cal."); ////c=12 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
|
||||
const char MSG_UNLOADING_FILAMENT[] PROGMEM_I1 = ISTR("Unloading filament"); ////c=20 r=1
|
||||
@ -104,13 +102,41 @@ const char MSG_WIZARD_QUIT[] PROGMEM_I1 = ISTR("You can always resume the Wizard
|
||||
const char MSG_YES[] PROGMEM_I1 = ISTR("Yes"); ////
|
||||
const char MSG_V2_CALIBRATION[] PROGMEM_I1 = ISTR("First layer cal."); ////c=17 r=1
|
||||
const char WELCOME_MSG[] PROGMEM_I1 = ISTR(CUSTOM_MENDEL_NAME " OK."); ////c=20
|
||||
const char MSG_OFF[] PROGMEM_I1 = ISTR("Off"); ////
|
||||
const char MSG_ON[] PROGMEM_I1 = ISTR("On"); ////
|
||||
const char MSG_NA[] PROGMEM_I1 = ISTR("N/A"); ////
|
||||
const char MSG_AUTO_DEPLETE[] PROGMEM_I1 = ISTR("SpoolJoin"); ////
|
||||
const char MSG_CUTTER[] PROGMEM_I1 = ISTR("Cutter"); ////
|
||||
const char MSG_NONE[] PROGMEM_I1 = ISTR("None"); ////
|
||||
const char MSG_WARN[] PROGMEM_I1 = ISTR("Warn"); ////
|
||||
const char MSG_STRICT[] PROGMEM_I1 = ISTR("Strict"); ////
|
||||
const char MSG_MODEL[] PROGMEM_I1 = ISTR("Model"); ////
|
||||
const char MSG_FIRMWARE[] PROGMEM_I1 = ISTR("Firmware"); ////
|
||||
const char MSG_GCODE[] PROGMEM_I1 = ISTR("Gcode"); ////
|
||||
const char MSG_NOZZLE_DIAMETER[] PROGMEM_I1 = ISTR("Nozzle d."); ////
|
||||
const char MSG_MMU_MODE[] PROGMEM_I1 = ISTR("MMU Mode"); ////
|
||||
const char MSG_SD_CARD[] PROGMEM_I1 = ISTR("SD card"); ////
|
||||
const char MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY[] PROGMEM_I1 = ISTR("FlashAir"); ////
|
||||
const char MSG_SORT[] PROGMEM_I1 = ISTR("Sort"); ////
|
||||
const char MSG_SORT_TIME[] PROGMEM_I1 = ISTR("Time"); ////
|
||||
const char MSG_SORT_ALPHA[] PROGMEM_I1 = ISTR("Alphabet"); ////
|
||||
const char MSG_RPI_PORT[] PROGMEM_I1 = ISTR("RPi port"); ////
|
||||
const char MSG_SOUND[] PROGMEM_I1 = ISTR("Sound"); ////
|
||||
const char MSG_SOUND_LOUD[] PROGMEM_I1 = ISTR("Loud"); ////
|
||||
const char MSG_SOUND_ONCE[] PROGMEM_I1 = ISTR("Once"); ////
|
||||
const char MSG_SOUND_BLIND[] PROGMEM_I1 = ISTR("Assist"); ////
|
||||
const char MSG_MESH[] PROGMEM_I1 = ISTR("Mesh"); ////
|
||||
const char MSG_Z_PROBE_NR[] PROGMEM_I1 = ISTR("Z-probe nr."); ////
|
||||
const char MSG_MAGNETS_COMP[] PROGMEM_I1 = ISTR("Magnets comp."); ////
|
||||
const char MSG_FS_ACTION[] PROGMEM_I1 = ISTR("FS Action"); ////
|
||||
const char MSG_FS_CONTINUE[] PROGMEM_I1 = ISTR("Cont."); ////
|
||||
const char MSG_FS_PAUSE[] PROGMEM_I1 = ISTR("Pause"); ////
|
||||
|
||||
//not internationalized messages
|
||||
const char MSG_SD_WORKDIR_FAIL[] PROGMEM_N1 = "workDir open failed"; ////
|
||||
const char MSG_BROWNOUT_RESET[] PROGMEM_N1 = " Brown out Reset"; ////
|
||||
const char MSG_EXTERNAL_RESET[] PROGMEM_N1 = " External Reset"; ////
|
||||
const char MSG_FILE_SAVED[] PROGMEM_N1 = "Done saving file."; ////
|
||||
const char MSG_OFF[] PROGMEM_N1 = "Off"; ////
|
||||
const char MSG_ON[] PROGMEM_N1 = "On "; ////
|
||||
const char MSG_POSITION_UNKNOWN[] PROGMEM_N1 = "Home X/Y before Z"; ////
|
||||
const char MSG_SOFTWARE_RESET[] PROGMEM_N1 = " Software Reset"; ////
|
||||
const char MSG_UNKNOWN_COMMAND[] PROGMEM_N1 = "Unknown command: \""; ////
|
||||
@ -129,4 +155,8 @@ const char MSG_ENDSTOP_OPEN[] PROGMEM_N1 = "open"; ////
|
||||
const char MSG_POWERUP[] PROGMEM_N1 = "PowerUp"; ////
|
||||
const char MSG_ERR_STOPPED[] PROGMEM_N1 = "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"; ////
|
||||
const char MSG_ENDSTOP_HIT[] PROGMEM_N1 = "TRIGGERED"; ////
|
||||
const char MSG_OCTOPRINT_PAUSE[] PROGMEM_N1 = "// action:pause"; ////
|
||||
const char MSG_OCTOPRINT_PAUSED[] PROGMEM_N1 = "// action:paused"; ////
|
||||
const char MSG_OCTOPRINT_RESUMED[] PROGMEM_N1 = "// action:resumed"; ////
|
||||
const char MSG_OCTOPRINT_CANCEL[] PROGMEM_N1 = "// action:cancel"; ////
|
||||
const char MSG_FANCHECK_EXTRUDER[] PROGMEM_N1 = "Err: EXTR. FAN ERROR"; ////c=20
|
||||
const char MSG_FANCHECK_PRINT[] PROGMEM_N1 = "Err: PRINT FAN ERROR"; ////c=20
|
||||
|
@ -10,7 +10,6 @@ extern "C" {
|
||||
// LCD Menu Messages
|
||||
//internationalized messages
|
||||
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[];
|
||||
@ -23,9 +22,7 @@ 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_CRASHDETECT[];
|
||||
extern const char MSG_ERROR[];
|
||||
extern const char MSG_EXTRUDER[];
|
||||
extern const char MSG_FILAMENT[];
|
||||
@ -41,9 +38,8 @@ 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_FOLLOW_Z_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_FSENSOR_AUTOLOAD[];
|
||||
extern const char MSG_FSENSOR[];
|
||||
extern const char MSG_HEATING[];
|
||||
extern const char MSG_HEATING_COMPLETE[];
|
||||
extern const char MSG_HOMEYZ[];
|
||||
@ -85,10 +81,12 @@ extern const char MSG_SELFTEST_FILAMENT_SENSOR[];
|
||||
extern const char MSG_SELFTEST_WIRINGERROR[];
|
||||
extern const char MSG_SETTINGS[];
|
||||
extern const char MSG_HW_SETUP[];
|
||||
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_MODE[];
|
||||
extern const char MSG_HIGH_POWER[];
|
||||
extern const char MSG_AUTO_POWER[];
|
||||
extern const char MSG_SILENT[];
|
||||
extern const char MSG_NORMAL[];
|
||||
extern const char MSG_STEALTH[];
|
||||
extern const char MSG_STEEL_SHEET_CHECK[];
|
||||
extern const char MSG_STOP_PRINT[];
|
||||
extern const char MSG_STOPPED[];
|
||||
@ -104,12 +102,40 @@ extern const char MSG_WIZARD_QUIT[];
|
||||
extern const char MSG_YES[];
|
||||
extern const char MSG_V2_CALIBRATION[];
|
||||
extern const char WELCOME_MSG[];
|
||||
extern const char MSG_OFF[];
|
||||
extern const char MSG_ON[];
|
||||
extern const char MSG_NA[];
|
||||
extern const char MSG_AUTO_DEPLETE[];
|
||||
extern const char MSG_CUTTER[];
|
||||
extern const char MSG_NONE[];
|
||||
extern const char MSG_WARN[];
|
||||
extern const char MSG_STRICT[];
|
||||
extern const char MSG_MODEL[];
|
||||
extern const char MSG_FIRMWARE[];
|
||||
extern const char MSG_GCODE[];
|
||||
extern const char MSG_NOZZLE_DIAMETER[];
|
||||
extern const char MSG_MMU_MODE[];
|
||||
extern const char MSG_SD_CARD[];
|
||||
extern const char MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY[];
|
||||
extern const char MSG_SORT[];
|
||||
extern const char MSG_SORT_TIME[];
|
||||
extern const char MSG_SORT_ALPHA[];
|
||||
extern const char MSG_RPI_PORT[];
|
||||
extern const char MSG_SOUND[];
|
||||
extern const char MSG_SOUND_LOUD[];
|
||||
extern const char MSG_SOUND_ONCE[];
|
||||
extern const char MSG_SOUND_BLIND[];
|
||||
extern const char MSG_MESH[];
|
||||
extern const char MSG_Z_PROBE_NR[];
|
||||
extern const char MSG_MAGNETS_COMP[];
|
||||
extern const char MSG_FS_ACTION[];
|
||||
extern const char MSG_FS_CONTINUE[];
|
||||
extern const char MSG_FS_PAUSE[];
|
||||
|
||||
//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[];
|
||||
@ -130,7 +156,11 @@ extern const char MSG_ERR_STOPPED[];
|
||||
extern const char MSG_ENDSTOP_HIT[];
|
||||
extern const char MSG_EJECT_FILAMENT[];
|
||||
extern const char MSG_CUT_FILAMENT[];
|
||||
extern const char MSG_OCTOPRINT_PAUSE[];
|
||||
extern const char MSG_OCTOPRINT_PAUSED[];
|
||||
extern const char MSG_OCTOPRINT_RESUMED[];
|
||||
extern const char MSG_OCTOPRINT_CANCEL[];
|
||||
extern const char MSG_FANCHECK_EXTRUDER[];
|
||||
extern const char MSG_FANCHECK_PRINT[];
|
||||
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
|
115
Firmware/mmu.cpp
115
Firmware/mmu.cpp
@ -70,6 +70,7 @@ uint8_t mmu_extruder = MMU_FILAMENT_UNKNOWN;
|
||||
uint8_t tmp_extruder = MMU_FILAMENT_UNKNOWN;
|
||||
|
||||
int8_t mmu_finda = -1;
|
||||
uint32_t mmu_last_finda_response = 0;
|
||||
|
||||
int16_t mmu_version = -1;
|
||||
|
||||
@ -264,6 +265,7 @@ void mmu_loop(void)
|
||||
if (mmu_rx_ok() > 0)
|
||||
{
|
||||
fscanf_P(uart2io, PSTR("%hhu"), &mmu_finda); //scan finda from buffer
|
||||
mmu_last_finda_response = _millis();
|
||||
FDEBUG_PRINTF_P(PSTR("MMU => '%dok'\n"), mmu_finda);
|
||||
puts_P(PSTR("MMU - ENABLED"));
|
||||
mmu_enabled = true;
|
||||
@ -376,11 +378,11 @@ void mmu_loop(void)
|
||||
if (mmu_rx_ok() > 0)
|
||||
{
|
||||
fscanf_P(uart2io, PSTR("%hhu"), &mmu_finda); //scan finda from buffer
|
||||
mmu_last_finda_response = _millis();
|
||||
FDEBUG_PRINTF_P(PSTR("MMU => '%dok'\n"), mmu_finda);
|
||||
//printf_P(PSTR("Eact: %d\n"), int(e_active()));
|
||||
if (!mmu_finda && CHECK_FSENSOR && fsensor_enabled) {
|
||||
fsensor_stop_and_save_print();
|
||||
enquecommand_front_P(PSTR("PRUSA fsensor_recover")); //then recover
|
||||
fsensor_checkpoint_print();
|
||||
ad_markDepleted(mmu_extruder);
|
||||
if (lcd_autoDepleteEnabled() && !ad_allDepleted())
|
||||
{
|
||||
@ -537,7 +539,7 @@ void mmu_command(MmuCmd cmd)
|
||||
void mmu_load_step(bool synchronize)
|
||||
{
|
||||
current_position[E_AXIS] = current_position[E_AXIS] + MMU_LOAD_FEEDRATE * 0.1;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], MMU_LOAD_FEEDRATE, active_extruder);
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
|
||||
if (synchronize) st_synchronize();
|
||||
}
|
||||
|
||||
@ -602,7 +604,7 @@ bool mmu_get_response(uint8_t move)
|
||||
{
|
||||
printf_P(PSTR("Unload 1\n"));
|
||||
current_position[E_AXIS] = current_position[E_AXIS] - MMU_LOAD_FEEDRATE * MMU_LOAD_TIME_MS*0.001;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], MMU_LOAD_FEEDRATE, active_extruder);
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
|
||||
st_synchronize();
|
||||
}
|
||||
}
|
||||
@ -620,7 +622,7 @@ bool mmu_get_response(uint8_t move)
|
||||
{
|
||||
printf_P(PSTR("Unload 2\n"));
|
||||
current_position[E_AXIS] = current_position[E_AXIS] - MMU_LOAD_FEEDRATE * MMU_LOAD_TIME_MS*0.001;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], MMU_LOAD_FEEDRATE, active_extruder);
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
|
||||
st_synchronize();
|
||||
}
|
||||
}
|
||||
@ -698,13 +700,13 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
|
||||
//lift z
|
||||
current_position[Z_AXIS] += Z_PAUSE_LIFT;
|
||||
if (current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder);
|
||||
plan_buffer_line_curposXYZE(15, active_extruder);
|
||||
st_synchronize();
|
||||
|
||||
//Move XY to side
|
||||
current_position[X_AXIS] = X_PAUSE_POS;
|
||||
current_position[Y_AXIS] = Y_PAUSE_POS;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder);
|
||||
plan_buffer_line_curposXYZE(50, active_extruder);
|
||||
st_synchronize();
|
||||
}
|
||||
if (turn_off_nozzle) {
|
||||
@ -762,10 +764,10 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
|
||||
lcd_display_message_fullscreen_P(_i("MMU OK. Resuming position..."));
|
||||
current_position[X_AXIS] = x_position_bckp;
|
||||
current_position[Y_AXIS] = y_position_bckp;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder);
|
||||
plan_buffer_line_curposXYZE(50, active_extruder);
|
||||
st_synchronize();
|
||||
current_position[Z_AXIS] = z_position_bckp;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder);
|
||||
plan_buffer_line_curposXYZE(15, active_extruder);
|
||||
st_synchronize();
|
||||
}
|
||||
else {
|
||||
@ -804,19 +806,19 @@ void mmu_load_to_nozzle()
|
||||
current_position[E_AXIS] += 7.2f;
|
||||
}
|
||||
float feedrate = 562;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
|
||||
st_synchronize();
|
||||
current_position[E_AXIS] += 14.4f;
|
||||
feedrate = 871;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
|
||||
st_synchronize();
|
||||
current_position[E_AXIS] += 36.0f;
|
||||
feedrate = 1393;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
|
||||
st_synchronize();
|
||||
current_position[E_AXIS] += 14.4f;
|
||||
feedrate = 871;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
|
||||
st_synchronize();
|
||||
if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = false;
|
||||
}
|
||||
@ -889,7 +891,7 @@ void mmu_M600_load_filament(bool automatic, float nozzle_temp)
|
||||
mmu_command(MmuCmd::T0 + tmp_extruder);
|
||||
|
||||
manage_response(false, true, MMU_LOAD_MOVE);
|
||||
mmu_continue_loading(is_usb_printing);
|
||||
mmu_continue_loading(is_usb_printing || (lcd_commands_type == LcdCommands::Layer1Cal));
|
||||
mmu_extruder = tmp_extruder; //filament change is finished
|
||||
|
||||
mmu_load_to_nozzle();
|
||||
@ -903,7 +905,7 @@ void extr_mov(float shift, float feed_rate)
|
||||
{ //move extruder no matter what the current heater temperature is
|
||||
set_extrude_min_temp(.0);
|
||||
current_position[E_AXIS] += shift;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feed_rate, active_extruder);
|
||||
plan_buffer_line_curposXYZE(feed_rate, active_extruder);
|
||||
set_extrude_min_temp(EXTRUDE_MINTEMP);
|
||||
}
|
||||
#endif //SNMM
|
||||
@ -978,7 +980,7 @@ void extr_adj(uint8_t extruder) //loading filament for SNMM
|
||||
{
|
||||
#ifndef SNMM
|
||||
MmuCmd cmd = MmuCmd::L0 + extruder;
|
||||
if (cmd > MmuCmd::L4)
|
||||
if (extruder > (MmuCmd::L4 - MmuCmd::L0))
|
||||
{
|
||||
printf_P(PSTR("Filament out of range %d \n"),extruder);
|
||||
return;
|
||||
@ -1069,33 +1071,11 @@ void mmu_filament_ramming()
|
||||
for(uint8_t i = 0; i < (sizeof(ramming_sequence)/sizeof(E_step));++i)
|
||||
{
|
||||
current_position[E_AXIS] += pgm_read_float(&(ramming_sequence[i].extrude));
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS],
|
||||
current_position[E_AXIS], pgm_read_float(&(ramming_sequence[i].feed_rate)), active_extruder);
|
||||
plan_buffer_line_curposXYZE(pgm_read_float(&(ramming_sequence[i].feed_rate)), active_extruder);
|
||||
st_synchronize();
|
||||
}
|
||||
}
|
||||
|
||||
//-//
|
||||
void extr_unload_()
|
||||
{
|
||||
//if(bFilamentAction)
|
||||
if(0)
|
||||
{
|
||||
bFilamentAction=false;
|
||||
extr_unload();
|
||||
}
|
||||
else {
|
||||
eFilamentAction=FilamentAction::MmuUnLoad;
|
||||
bFilamentFirstRun=false;
|
||||
if(target_temperature[0]>=EXTRUDE_MINTEMP)
|
||||
{
|
||||
bFilamentPreheatState=true;
|
||||
mFilamentItem(target_temperature[0],target_temperature_bed);
|
||||
}
|
||||
// else menu_submenu(mFilamentMenu);
|
||||
else mFilamentMenu();
|
||||
}
|
||||
}
|
||||
|
||||
//! @brief show which filament is currently unloaded
|
||||
void extr_unload_view()
|
||||
@ -1140,39 +1120,39 @@ void extr_unload()
|
||||
lcd_set_cursor(0, 2); lcd_puts_P(_T(MSG_PLEASE_WAIT));
|
||||
if (current_position[Z_AXIS] < 15) {
|
||||
current_position[Z_AXIS] += 15; //lifting in Z direction to make space for extrusion
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 25, active_extruder);
|
||||
plan_buffer_line_curposXYZE(25, active_extruder);
|
||||
}
|
||||
|
||||
current_position[E_AXIS] += 10; //extrusion
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 10, active_extruder);
|
||||
plan_buffer_line_curposXYZE(10, active_extruder);
|
||||
st_current_set(2, E_MOTOR_HIGH_CURRENT);
|
||||
if (current_temperature[0] < 230) { //PLA & all other filaments
|
||||
current_position[E_AXIS] += 5.4;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2800 / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(2800 / 60, active_extruder);
|
||||
current_position[E_AXIS] += 3.2;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
|
||||
current_position[E_AXIS] += 3;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3400 / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(3400 / 60, active_extruder);
|
||||
}
|
||||
else { //ABS
|
||||
current_position[E_AXIS] += 3.1;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2000 / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(2000 / 60, active_extruder);
|
||||
current_position[E_AXIS] += 3.1;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(2500 / 60, active_extruder);
|
||||
current_position[E_AXIS] += 4;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder);
|
||||
plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
|
||||
/*current_position[X_AXIS] += 23; //delay
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder); //delay
|
||||
plan_buffer_line_curposXYZE(600 / 60, active_extruder); //delay
|
||||
current_position[X_AXIS] -= 23; //delay
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder); //delay*/
|
||||
plan_buffer_line_curposXYZE(600 / 60, active_extruder); //delay*/
|
||||
delay_keep_alive(4700);
|
||||
}
|
||||
|
||||
max_feedrate[E_AXIS] = 80;
|
||||
current_position[E_AXIS] -= (bowden_length[mmu_extruder] + 60 + FIL_LOAD_LENGTH) / 2;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 500, active_extruder);
|
||||
plan_buffer_line_curposXYZE(500, active_extruder);
|
||||
current_position[E_AXIS] -= (bowden_length[mmu_extruder] + 60 + FIL_LOAD_LENGTH) / 2;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 500, active_extruder);
|
||||
plan_buffer_line_curposXYZE(500, active_extruder);
|
||||
st_synchronize();
|
||||
//st_current_init();
|
||||
if (SilentMode != SILENT_MODE_OFF) st_current_set(2, tmp_motor[2]); //set back to normal operation currents
|
||||
@ -1377,7 +1357,7 @@ void lcd_mmu_load_to_nozzle(uint8_t filament_nr)
|
||||
manage_response(true, true, MMU_TCODE_MOVE);
|
||||
mmu_continue_loading(false);
|
||||
mmu_extruder = tmp_extruder; //filament change is finished
|
||||
marlin_rise_z();
|
||||
raise_z_above(MIN_Z_FOR_LOAD, false);
|
||||
mmu_load_to_nozzle();
|
||||
load_filament_final_feed();
|
||||
st_synchronize();
|
||||
@ -1465,11 +1445,9 @@ bFilamentAction=false; // NOT in "mmu_fil_eject_menu(
|
||||
static bool can_load()
|
||||
{
|
||||
current_position[E_AXIS] += 60;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS],
|
||||
current_position[E_AXIS], MMU_LOAD_FEEDRATE, active_extruder);
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
|
||||
current_position[E_AXIS] -= 52;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS],
|
||||
current_position[E_AXIS], MMU_LOAD_FEEDRATE, active_extruder);
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
|
||||
st_synchronize();
|
||||
|
||||
uint_least8_t filament_detected_count = 0;
|
||||
@ -1479,8 +1457,7 @@ static bool can_load()
|
||||
for(uint_least8_t i = 0; i < steps; ++i)
|
||||
{
|
||||
current_position[E_AXIS] -= e_increment;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS],
|
||||
current_position[E_AXIS], MMU_LOAD_FEEDRATE, active_extruder);
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
|
||||
st_synchronize();
|
||||
if(0 == PIN_GET(IR_SENSOR_PIN))
|
||||
{
|
||||
@ -1581,19 +1558,23 @@ void mmu_continue_loading(bool blocking)
|
||||
increment_load_fail();
|
||||
// no break
|
||||
case Ls::Retry:
|
||||
#ifdef MMU_HAS_CUTTER
|
||||
if (1 == eeprom_read_byte((uint8_t*)EEPROM_MMU_CUTTER_ENABLED))
|
||||
++retry; // overflow not handled, as it is not dangerous.
|
||||
if (retry >= max_retry)
|
||||
{
|
||||
mmu_command(MmuCmd::K0 + tmp_extruder);
|
||||
manage_response(true, true, MMU_UNLOAD_MOVE);
|
||||
}
|
||||
state = Ls::Unload;
|
||||
#ifdef MMU_HAS_CUTTER
|
||||
if (1 == eeprom_read_byte((uint8_t*)EEPROM_MMU_CUTTER_ENABLED))
|
||||
{
|
||||
mmu_command(MmuCmd::K0 + tmp_extruder);
|
||||
manage_response(true, true, MMU_UNLOAD_MOVE);
|
||||
}
|
||||
#endif //MMU_HAS_CUTTER
|
||||
}
|
||||
mmu_command(MmuCmd::T0 + tmp_extruder);
|
||||
manage_response(true, true, MMU_TCODE_MOVE);
|
||||
success = load_more();
|
||||
if (success) success = can_load();
|
||||
++retry; // overflow not handled, as it is not dangerous.
|
||||
if (retry >= max_retry) state = Ls::Unload;
|
||||
|
||||
break;
|
||||
case Ls::Unload:
|
||||
stop_and_save_print_to_ram(0, 0);
|
||||
@ -1601,13 +1582,13 @@ void mmu_continue_loading(bool blocking)
|
||||
//lift z
|
||||
current_position[Z_AXIS] += Z_PAUSE_LIFT;
|
||||
if (current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder);
|
||||
plan_buffer_line_curposXYZE(15, active_extruder);
|
||||
st_synchronize();
|
||||
|
||||
//Move XY to side
|
||||
current_position[X_AXIS] = X_PAUSE_POS;
|
||||
current_position[Y_AXIS] = Y_PAUSE_POS;
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder);
|
||||
plan_buffer_line_curposXYZE(50, active_extruder);
|
||||
st_synchronize();
|
||||
|
||||
mmu_command(MmuCmd::U0);
|
||||
|
@ -14,6 +14,7 @@ extern uint8_t mmu_extruder;
|
||||
extern uint8_t tmp_extruder;
|
||||
|
||||
extern int8_t mmu_finda;
|
||||
extern uint32_t mmu_last_finda_response;
|
||||
extern bool ir_sensor_detected;
|
||||
|
||||
extern int16_t mmu_version;
|
||||
@ -105,8 +106,7 @@ extern int get_ext_nr();
|
||||
extern void display_loading();
|
||||
extern void extr_adj(uint8_t extruder);
|
||||
extern void extr_unload();
|
||||
//-//
|
||||
extern void extr_unload_();
|
||||
|
||||
extern void extr_adj_0();
|
||||
extern void extr_adj_1();
|
||||
extern void extr_adj_2();
|
||||
|
@ -71,12 +71,13 @@
|
||||
#define HEATER_2_PIN -1
|
||||
#define TEMP_2_PIN -1
|
||||
|
||||
#define TEMP_AMBIENT_PIN 5 //A5
|
||||
#define TEMP_AMBIENT_PIN 6 //A6
|
||||
|
||||
#define TEMP_PINDA_PIN 3 //A3
|
||||
|
||||
#define VOLT_PWR_PIN 4 //A4
|
||||
#define VOLT_BED_PIN 9 //A9
|
||||
#define VOLT_IR_PIN 8 //A8
|
||||
|
||||
|
||||
#define E0_TMC2130_CS 66
|
||||
|
@ -651,19 +651,23 @@ void planner_abort_hard()
|
||||
waiting_inside_plan_buffer_line_print_aborted = true;
|
||||
}
|
||||
|
||||
void plan_buffer_line_curposXYZE(float feed_rate, uint8_t extruder) {
|
||||
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feed_rate, extruder );
|
||||
}
|
||||
|
||||
float junction_deviation = 0.1;
|
||||
// Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in
|
||||
// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
|
||||
// calculation the caller must also provide the physical length of the line in millimeters.
|
||||
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder)
|
||||
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, uint8_t extruder, const float* gcode_target)
|
||||
{
|
||||
// Calculate the buffer head after we push this byte
|
||||
int next_buffer_head = next_block_index(block_buffer_head);
|
||||
|
||||
// If the buffer is full: good! That means we are well ahead of the robot.
|
||||
// Rest here until there is room in the buffer.
|
||||
waiting_inside_plan_buffer_line_print_aborted = false;
|
||||
if (block_buffer_tail == next_buffer_head) {
|
||||
waiting_inside_plan_buffer_line_print_aborted = false;
|
||||
do {
|
||||
manage_heater();
|
||||
// Vojtech: Don't disable motors inside the planner!
|
||||
@ -683,6 +687,29 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
||||
planner_update_queue_min_counter();
|
||||
#endif /* PLANNER_DIAGNOSTICS */
|
||||
|
||||
// Prepare to set up new block
|
||||
block_t *block = &block_buffer[block_buffer_head];
|
||||
|
||||
// Mark block as not busy (Not executed by the stepper interrupt, could be still tinkered with.)
|
||||
block->busy = false;
|
||||
|
||||
// Set sdlen for calculating sd position
|
||||
block->sdlen = 0;
|
||||
|
||||
// Save original destination of the move
|
||||
if (gcode_target)
|
||||
memcpy(block->gcode_target, gcode_target, sizeof(block_t::gcode_target));
|
||||
else
|
||||
{
|
||||
block->gcode_target[X_AXIS] = x;
|
||||
block->gcode_target[Y_AXIS] = y;
|
||||
block->gcode_target[Z_AXIS] = z;
|
||||
block->gcode_target[E_AXIS] = e;
|
||||
}
|
||||
|
||||
// Save the global feedrate at scheduling time
|
||||
block->gcode_feedrate = feedrate;
|
||||
|
||||
#ifdef ENABLE_AUTO_BED_LEVELING
|
||||
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
|
||||
#endif // ENABLE_AUTO_BED_LEVELING
|
||||
@ -782,15 +809,6 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
||||
}
|
||||
#endif
|
||||
|
||||
// Prepare to set up new block
|
||||
block_t *block = &block_buffer[block_buffer_head];
|
||||
|
||||
// Set sdlen for calculating sd position
|
||||
block->sdlen = 0;
|
||||
|
||||
// Mark block as not busy (Not executed by the stepper interrupt, could be still tinkered with.)
|
||||
block->busy = false;
|
||||
|
||||
// Number of steps for each axis
|
||||
#ifndef COREXY
|
||||
// default non-h-bot planning
|
||||
|
@ -116,7 +116,10 @@ typedef struct {
|
||||
unsigned long abs_adv_steps_multiplier8; // Factorised by 2^8 to avoid float
|
||||
#endif
|
||||
|
||||
uint16_t sdlen;
|
||||
// Save/recovery state data
|
||||
float gcode_target[NUM_AXIS]; // Target (abs mm) of the original Gcode instruction
|
||||
uint16_t gcode_feedrate; // Default and/or move feedrate
|
||||
uint16_t sdlen; // Length of the Gcode instruction
|
||||
} block_t;
|
||||
|
||||
#ifdef LIN_ADVANCE
|
||||
@ -140,7 +143,14 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate
|
||||
// Get the position applying the bed level matrix if enabled
|
||||
vector_3 plan_get_position();
|
||||
#else
|
||||
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder);
|
||||
|
||||
/// Extracting common call of
|
||||
/// plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], ...
|
||||
/// saves almost 5KB.
|
||||
/// The performance penalty is negligible, since these planned lines are usually maintenance moves with the extruder.
|
||||
void plan_buffer_line_curposXYZE(float feed_rate, uint8_t extruder);
|
||||
|
||||
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, uint8_t extruder, const float* gcode_target = NULL);
|
||||
//void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder);
|
||||
#endif // ENABLE_AUTO_BED_LEVELING
|
||||
|
||||
@ -231,6 +241,7 @@ FORCE_INLINE bool planner_queue_full() {
|
||||
// wait for the steppers to stop,
|
||||
// update planner's current position and the current_position of the front end.
|
||||
extern void planner_abort_hard();
|
||||
extern bool waiting_inside_plan_buffer_line_print_aborted;
|
||||
|
||||
#ifdef PREVENT_DANGEROUS_EXTRUDE
|
||||
void set_extrude_min_temp(float temp);
|
||||
|
@ -135,10 +135,15 @@ switch(eSoundMode)
|
||||
|
||||
static void Sound_DoSound_Blind_Alert(void)
|
||||
{
|
||||
_tone(BEEPER,300);
|
||||
_delay_ms(75);
|
||||
_noTone(BEEPER);
|
||||
_delay_ms(75);
|
||||
uint8_t nI;
|
||||
|
||||
for(nI=0; nI<20; nI++)
|
||||
{
|
||||
WRITE(BEEPER,HIGH);
|
||||
delayMicroseconds(94);
|
||||
WRITE(BEEPER,LOW);
|
||||
delayMicroseconds(94);
|
||||
}
|
||||
}
|
||||
|
||||
static void Sound_DoSound_Encoder_Move(void)
|
||||
|
@ -3,12 +3,6 @@
|
||||
#define SOUND_H
|
||||
|
||||
|
||||
#define MSG_SOUND_MODE_LOUD "Sound [loud]"
|
||||
#define MSG_SOUND_MODE_ONCE "Sound [once]"
|
||||
#define MSG_SOUND_MODE_SILENT "Sound [silent]"
|
||||
#define MSG_SOUND_MODE_BLIND "Sound [blind]"
|
||||
|
||||
|
||||
#define e_SOUND_MODE_NULL 0xFF
|
||||
typedef enum
|
||||
{e_SOUND_MODE_LOUD,e_SOUND_MODE_ONCE,e_SOUND_MODE_SILENT,e_SOUND_MODE_BLIND} eSOUND_MODE;
|
||||
|
@ -1561,10 +1561,10 @@ void EEPROM_read_st(int pos, uint8_t* value, uint8_t size)
|
||||
|
||||
|
||||
void st_current_init() //Initialize Digipot Motor Current
|
||||
{
|
||||
uint8_t SilentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
|
||||
{
|
||||
#ifdef MOTOR_CURRENT_PWM_XY_PIN
|
||||
uint8_t SilentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
|
||||
SilentModeMenu = SilentMode;
|
||||
#ifdef MOTOR_CURRENT_PWM_XY_PIN
|
||||
pinMode(MOTOR_CURRENT_PWM_XY_PIN, OUTPUT);
|
||||
pinMode(MOTOR_CURRENT_PWM_Z_PIN, OUTPUT);
|
||||
pinMode(MOTOR_CURRENT_PWM_E_PIN, OUTPUT);
|
||||
@ -1586,7 +1586,7 @@ uint8_t SilentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
|
||||
st_current_set(2, motor_current_setting[2]);
|
||||
//Set timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise)
|
||||
TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@ -44,6 +44,8 @@
|
||||
#include "Timer.h"
|
||||
#include "Configuration_prusa.h"
|
||||
|
||||
#include "config.h"
|
||||
|
||||
//===========================================================================
|
||||
//=============================public variables============================
|
||||
//===========================================================================
|
||||
@ -71,12 +73,12 @@ int current_voltage_raw_pwr = 0;
|
||||
int current_voltage_raw_bed = 0;
|
||||
#endif
|
||||
|
||||
#if IR_SENSOR_ANALOG
|
||||
int current_voltage_raw_IR = 0;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
int current_temperature_bed_raw = 0;
|
||||
float current_temperature_bed = 0.0;
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
int redundant_temperature_raw = 0;
|
||||
float redundant_temperature = 0.0;
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef PIDTEMP
|
||||
@ -175,13 +177,8 @@ static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP;
|
||||
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
|
||||
#endif
|
||||
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
static void *heater_ttbl_map[2] = {(void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE };
|
||||
static uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN };
|
||||
#else
|
||||
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
|
||||
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
|
||||
#endif
|
||||
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
|
||||
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
|
||||
|
||||
static float analog2temp(int raw, uint8_t e);
|
||||
static float analog2tempBed(int raw);
|
||||
@ -195,11 +192,6 @@ enum TempRunawayStates
|
||||
TempRunaway_ACTIVE = 2,
|
||||
};
|
||||
|
||||
#ifdef WATCH_TEMP_PERIOD
|
||||
int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
|
||||
unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
|
||||
#endif //WATCH_TEMP_PERIOD
|
||||
|
||||
#ifndef SOFT_PWM_SCALE
|
||||
#define SOFT_PWM_SCALE 0
|
||||
#endif
|
||||
@ -517,14 +509,17 @@ void checkFanSpeed()
|
||||
// drop the fan_check_error flag when both fans are ok
|
||||
if( fan_speed_errors[0] == 0 && fan_speed_errors[1] == 0 && fan_check_error == EFCE_REPORTED){
|
||||
// we may even send some info to the LCD from here
|
||||
fan_check_error = EFCE_OK;
|
||||
fan_check_error = EFCE_FIXED;
|
||||
}
|
||||
|
||||
if ((fan_speed_errors[0] > max_extruder_fan_errors) && fans_check_enabled) {
|
||||
if ((fan_check_error == EFCE_FIXED) && !PRINTER_ACTIVE){
|
||||
fan_check_error = EFCE_OK; //if the issue is fixed while the printer is doing nothing, reenable processing immediately.
|
||||
lcd_reset_alert_level(); //for another fan speed error
|
||||
}
|
||||
if ((fan_speed_errors[0] > max_extruder_fan_errors) && fans_check_enabled && (fan_check_error == EFCE_OK)) {
|
||||
fan_speed_errors[0] = 0;
|
||||
fanSpeedError(0); //extruder fan
|
||||
}
|
||||
if ((fan_speed_errors[1] > max_print_fan_errors) && fans_check_enabled) {
|
||||
if ((fan_speed_errors[1] > max_print_fan_errors) && fans_check_enabled && (fan_check_error == EFCE_OK)) {
|
||||
fan_speed_errors[1] = 0;
|
||||
fanSpeedError(1); //print fan
|
||||
}
|
||||
@ -543,31 +538,31 @@ static void fanSpeedErrorBeep(const char *serialMsg, const char *lcdMsg){
|
||||
}
|
||||
|
||||
void fanSpeedError(unsigned char _fan) {
|
||||
if (get_message_level() != 0 && isPrintPaused) return;
|
||||
//to ensure that target temp. is not set to zero in case taht we are resuming print
|
||||
if (get_message_level() != 0 && isPrintPaused) return;
|
||||
//to ensure that target temp. is not set to zero in case that we are resuming print
|
||||
if (card.sdprinting || is_usb_printing) {
|
||||
if (heating_status != 0) {
|
||||
lcd_print_stop();
|
||||
}
|
||||
else {
|
||||
fan_check_error = EFCE_DETECTED;
|
||||
fan_check_error = EFCE_DETECTED; //plans error for next processed command
|
||||
}
|
||||
}
|
||||
else {
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_OCTOPRINT_PAUSE); //for octoprint
|
||||
setTargetHotend0(0);
|
||||
heating_status = 0;
|
||||
fan_check_error = EFCE_REPORTED;
|
||||
// SERIAL_PROTOCOLLNRPGM(MSG_OCTOPRINT_PAUSED); //Why pause octoprint? is_usb_printing would be true in that case, so there is no need for this.
|
||||
setTargetHotend0(0);
|
||||
heating_status = 0;
|
||||
fan_check_error = EFCE_REPORTED;
|
||||
}
|
||||
switch (_fan) {
|
||||
case 0: // extracting the same code from case 0 and case 1 into a function saves 72B
|
||||
fanSpeedErrorBeep(PSTR("Extruder fan speed is lower than expected"), PSTR("Err: EXTR. FAN ERROR") );
|
||||
fanSpeedErrorBeep(PSTR("Extruder fan speed is lower than expected"), MSG_FANCHECK_EXTRUDER);
|
||||
break;
|
||||
case 1:
|
||||
fanSpeedErrorBeep(PSTR("Print fan speed is lower than expected"), PSTR("Err: PRINT FAN ERROR") );
|
||||
fanSpeedErrorBeep(PSTR("Print fan speed is lower than expected"), MSG_FANCHECK_PRINT);
|
||||
break;
|
||||
}
|
||||
SERIAL_PROTOCOLLNRPGM(MSG_OK);
|
||||
// SERIAL_PROTOCOLLNRPGM(MSG_OK); //This ok messes things up with octoprint.
|
||||
}
|
||||
#endif //(defined(TACH_0) && TACH_0 >-1) || (defined(TACH_1) && TACH_1 > -1)
|
||||
|
||||
@ -728,34 +723,6 @@ void manage_heater()
|
||||
{
|
||||
soft_pwm[e] = 0;
|
||||
}
|
||||
|
||||
#ifdef WATCH_TEMP_PERIOD
|
||||
if(watchmillis[e] && _millis() - watchmillis[e] > WATCH_TEMP_PERIOD)
|
||||
{
|
||||
if(degHotend(e) < watch_start_temp[e] + WATCH_TEMP_INCREASE)
|
||||
{
|
||||
setTargetHotend(0, e);
|
||||
LCD_MESSAGEPGM("Heating failed");
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLN("Heating failed");
|
||||
}else{
|
||||
watchmillis[e] = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
if(fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) {
|
||||
disable_heater();
|
||||
if(IsStopped() == false) {
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNPGM("Extruder switched off. Temperature difference between temp sensors is too high !");
|
||||
LCD_ALERTMESSAGEPGM("Err: REDUNDANT TEMP ERROR");
|
||||
}
|
||||
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
|
||||
Stop();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
} // End extruder for loop
|
||||
|
||||
#define FAN_CHECK_PERIOD 5000 //5s
|
||||
@ -907,11 +874,7 @@ void manage_heater()
|
||||
// Derived from RepRap FiveD extruder::getTemperature()
|
||||
// For hot end temperature measurement.
|
||||
static float analog2temp(int raw, uint8_t e) {
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
if(e > EXTRUDERS)
|
||||
#else
|
||||
if(e >= EXTRUDERS)
|
||||
#endif
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERROR((int)e);
|
||||
@ -1054,10 +1017,6 @@ static void updateTemperaturesFromRawValues()
|
||||
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
|
||||
#endif //DEBUG_HEATER_BED_SIM
|
||||
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
redundant_temperature = analog2temp(redundant_temperature_raw, 1);
|
||||
#endif
|
||||
|
||||
CRITICAL_SECTION_START;
|
||||
temp_meas_ready = false;
|
||||
CRITICAL_SECTION_END;
|
||||
@ -1221,20 +1180,6 @@ void tp_init()
|
||||
#endif //BED_MAXTEMP
|
||||
}
|
||||
|
||||
void setWatch()
|
||||
{
|
||||
#ifdef WATCH_TEMP_PERIOD
|
||||
for (int e = 0; e < EXTRUDERS; e++)
|
||||
{
|
||||
if(degHotend(e) < degTargetHotend(e) - (WATCH_TEMP_INCREASE * 2))
|
||||
{
|
||||
watch_start_temp[e] = degHotend(e);
|
||||
watchmillis[e] = _millis();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if (defined (TEMP_RUNAWAY_BED_HYSTERESIS) && TEMP_RUNAWAY_BED_TIMEOUT > 0) || (defined (TEMP_RUNAWAY_EXTRUDER_HYSTERESIS) && TEMP_RUNAWAY_EXTRUDER_TIMEOUT > 0)
|
||||
void temp_runaway_check(int _heater_id, float _target_temperature, float _current_temperature, float _output, bool _isbed)
|
||||
{
|
||||
@ -1629,17 +1574,22 @@ extern "C" {
|
||||
void adc_ready(void) //callback from adc when sampling finished
|
||||
{
|
||||
current_temperature_raw[0] = adc_values[ADC_PIN_IDX(TEMP_0_PIN)]; //heater
|
||||
#ifdef PINDA_THERMISTOR
|
||||
current_temperature_raw_pinda_fast = adc_values[ADC_PIN_IDX(TEMP_PINDA_PIN)];
|
||||
#endif //PINDA_THERMISTOR
|
||||
current_temperature_bed_raw = adc_values[ADC_PIN_IDX(TEMP_BED_PIN)];
|
||||
#ifdef VOLT_PWR_PIN
|
||||
current_voltage_raw_pwr = adc_values[ADC_PIN_IDX(VOLT_PWR_PIN)];
|
||||
#endif
|
||||
#ifdef AMBIENT_THERMISTOR
|
||||
current_temperature_raw_ambient = adc_values[ADC_PIN_IDX(TEMP_AMBIENT_PIN)];
|
||||
current_temperature_raw_ambient = adc_values[ADC_PIN_IDX(TEMP_AMBIENT_PIN)]; // 5->6
|
||||
#endif //AMBIENT_THERMISTOR
|
||||
#ifdef VOLT_BED_PIN
|
||||
current_voltage_raw_bed = adc_values[ADC_PIN_IDX(VOLT_BED_PIN)]; // 6->9
|
||||
#endif
|
||||
#if IR_SENSOR_ANALOG
|
||||
current_voltage_raw_IR = adc_values[ADC_PIN_IDX(VOLT_IR_PIN)];
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
temp_meas_ready = true;
|
||||
}
|
||||
|
||||
|
@ -27,6 +27,8 @@
|
||||
#include "stepper.h"
|
||||
#endif
|
||||
|
||||
#include "config.h"
|
||||
|
||||
|
||||
#ifdef SYSTEM_TIMER_2
|
||||
|
||||
@ -74,9 +76,9 @@ extern int current_voltage_raw_pwr;
|
||||
extern int current_voltage_raw_bed;
|
||||
#endif
|
||||
|
||||
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
|
||||
extern float redundant_temperature;
|
||||
#endif
|
||||
#if IR_SENSOR_ANALOG
|
||||
extern int current_voltage_raw_IR;
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
|
||||
extern unsigned char soft_pwm_bed;
|
||||
@ -220,7 +222,6 @@ FORCE_INLINE bool isCoolingBed() {
|
||||
|
||||
int getHeaterPower(int heater);
|
||||
void disable_heater();
|
||||
void setWatch();
|
||||
void updatePID();
|
||||
|
||||
|
||||
@ -245,6 +246,7 @@ void checkExtruderAutoFans();
|
||||
|
||||
enum {
|
||||
EFCE_OK = 0, //!< normal operation, both fans are ok
|
||||
EFCE_FIXED, //!< previous fan error was fixed
|
||||
EFCE_DETECTED, //!< fan error detected, but not reported yet
|
||||
EFCE_REPORTED //!< fan error detected and reported to LCD and serial
|
||||
};
|
||||
|
@ -26,7 +26,7 @@ void timer0_init(void)
|
||||
OCR0B = 255;
|
||||
// Set fast PWM mode and inverting mode.
|
||||
TCCR0A = (1 << WGM01) | (1 << WGM00) | (1 << COM0B1) | (1 << COM0B0);
|
||||
TCCR0B = (1 << CS00); // no clock prescaling
|
||||
TCCR0B = (1 << CS01); // CLK/8 prescaling
|
||||
TIMSK0 |= (1 << TOIE0); // enable timer overflow interrupt
|
||||
|
||||
// Everything, that used to be on timer0 was moved to timer2 (delay, beeping, millis etc.)
|
||||
|
@ -1,3 +1,5 @@
|
||||
//! @file
|
||||
|
||||
#include "Marlin.h"
|
||||
|
||||
#ifdef TMC2130
|
||||
@ -22,7 +24,7 @@ uint8_t tmc2130_current_h[4] = TMC2130_CURRENTS_H;
|
||||
uint8_t tmc2130_current_r[4] = TMC2130_CURRENTS_R;
|
||||
|
||||
//running currents for homing
|
||||
uint8_t tmc2130_current_r_home[4] = {8, 10, 20, 18};
|
||||
uint8_t tmc2130_current_r_home[4] = TMC2130_CURRENTS_R_HOME;
|
||||
|
||||
|
||||
//pwm_ampl
|
||||
@ -38,7 +40,7 @@ uint8_t tmc2130_mres[4] = {0, 0, 0, 0}; //will be filed at begin of init
|
||||
|
||||
|
||||
uint8_t tmc2130_sg_thr[4] = {TMC2130_SG_THRS_X, TMC2130_SG_THRS_Y, TMC2130_SG_THRS_Z, TMC2130_SG_THRS_E};
|
||||
uint8_t tmc2130_sg_thr_home[4] = {3, 3, TMC2130_SG_THRS_Z, TMC2130_SG_THRS_E};
|
||||
uint8_t tmc2130_sg_thr_home[4] = TMC2130_SG_THRS_HOME;
|
||||
|
||||
|
||||
uint8_t tmc2130_sg_homing_axes_mask = 0x00;
|
||||
@ -425,7 +427,7 @@ void tmc2130_check_overtemp()
|
||||
|
||||
void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_t current_r)
|
||||
{
|
||||
uint8_t intpol = 1;
|
||||
uint8_t intpol = (mres != 0); // intpol to 256 only if microsteps aren't 256
|
||||
uint8_t toff = tmc2130_chopper_config[axis].toff; // toff = 3 (fchop = 27.778kHz)
|
||||
uint8_t hstrt = tmc2130_chopper_config[axis].hstr; //initial 4, modified to 5
|
||||
uint8_t hend = tmc2130_chopper_config[axis].hend; //original value = 1
|
||||
@ -598,7 +600,7 @@ void tmc2130_wr_THIGH(uint8_t axis, uint32_t val32)
|
||||
|
||||
uint8_t tmc2130_usteps2mres(uint16_t usteps)
|
||||
{
|
||||
uint8_t mres = 8; while (mres && (usteps >>= 1)) mres--;
|
||||
uint8_t mres = 8; while (usteps >>= 1) mres--;
|
||||
return mres;
|
||||
}
|
||||
|
||||
@ -1009,6 +1011,79 @@ bool tmc2130_home_calibrate(uint8_t axis)
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
//! @brief Translate current to tmc2130 vsense and IHOLD or IRUN
|
||||
//! @param cur current in mA
|
||||
//! @return 0 .. 63
|
||||
//! @n most significant bit is CHOPCONF vsense bit (sense resistor voltage based current scaling)
|
||||
//! @n rest is to be used in IRUN or IHOLD register
|
||||
//!
|
||||
//! | mA | trinamic register | note |
|
||||
//! | --- | --- | --- |
|
||||
//! | 0 | 0 | doesn't mean current off, lowest current is 1/32 current with vsense low range |
|
||||
//! | 30 | 1 | |
|
||||
//! | 40 | 2 | |
|
||||
//! | 60 | 3 | |
|
||||
//! | 90 | 4 | |
|
||||
//! | 100 | 5 | |
|
||||
//! | 120 | 6 | |
|
||||
//! | 130 | 7 | |
|
||||
//! | 150 | 8 | |
|
||||
//! | 180 | 9 | |
|
||||
//! | 190 | 10 | |
|
||||
//! | 210 | 11 | |
|
||||
//! | 230 | 12 | |
|
||||
//! | 240 | 13 | |
|
||||
//! | 250 | 13 | |
|
||||
//! | 260 | 14 | |
|
||||
//! | 280 | 15 | |
|
||||
//! | 300 | 16 | |
|
||||
//! | 320 | 17 | |
|
||||
//! | 340 | 18 | |
|
||||
//! | 350 | 19 | |
|
||||
//! | 370 | 20 | |
|
||||
//! | 390 | 21 | |
|
||||
//! | 410 | 22 | |
|
||||
//! | 430 | 23 | |
|
||||
//! | 450 | 24 | |
|
||||
//! | 460 | 25 | |
|
||||
//! | 480 | 26 | |
|
||||
//! | 500 | 27 | |
|
||||
//! | 520 | 28 | |
|
||||
//! | 535 | 29 | |
|
||||
//! | N/D | 30 | extruder default |
|
||||
//! | 540 | 33 | |
|
||||
//! | 560 | 34 | |
|
||||
//! | 580 | 35 | |
|
||||
//! | 590 | 36 | farm mode extruder default |
|
||||
//! | 610 | 37 | |
|
||||
//! | 630 | 38 | |
|
||||
//! | 640 | 39 | |
|
||||
//! | 660 | 40 | |
|
||||
//! | 670 | 41 | |
|
||||
//! | 690 | 42 | |
|
||||
//! | 710 | 43 | |
|
||||
//! | 720 | 44 | |
|
||||
//! | 730 | 45 | |
|
||||
//! | 760 | 46 | |
|
||||
//! | 770 | 47 | |
|
||||
//! | 790 | 48 | |
|
||||
//! | 810 | 49 | |
|
||||
//! | 820 | 50 | |
|
||||
//! | 840 | 51 | |
|
||||
//! | 850 | 52 | |
|
||||
//! | 870 | 53 | |
|
||||
//! | 890 | 54 | |
|
||||
//! | 900 | 55 | |
|
||||
//! | 920 | 56 | |
|
||||
//! | 940 | 57 | |
|
||||
//! | 950 | 58 | |
|
||||
//! | 970 | 59 | |
|
||||
//! | 980 | 60 | |
|
||||
//! | 1000 | 61 | |
|
||||
//! | 1020 | 62 | |
|
||||
//! | 1029 | 63 | |
|
||||
|
||||
uint8_t tmc2130_cur2val(float cur)
|
||||
{
|
||||
if (cur < 0) cur = 0; //limit min
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -7,6 +7,8 @@
|
||||
#include "menu.h"
|
||||
#include "mesh_bed_calibration.h"
|
||||
|
||||
#include "config.h"
|
||||
|
||||
extern void menu_lcd_longpress_func(void);
|
||||
extern void menu_lcd_charsetup_func(void);
|
||||
extern void menu_lcd_lcdupdate_func(void);
|
||||
@ -47,12 +49,18 @@ unsigned char lcd_choose_color();
|
||||
void lcd_load_filament_color_check();
|
||||
//void lcd_mylang();
|
||||
|
||||
extern void lcd_belttest();
|
||||
extern bool lcd_selftest();
|
||||
|
||||
void lcd_menu_statistics();
|
||||
|
||||
void lcd_menu_extruder_info(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()")
|
||||
void lcd_menu_show_sensors_state(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()")
|
||||
#ifdef TMC2130
|
||||
bool lcd_crash_detect_enabled();
|
||||
void lcd_crash_detect_enable();
|
||||
void lcd_crash_detect_disable();
|
||||
#endif
|
||||
|
||||
extern const char* lcd_display_message_fullscreen_P(const char *msg, uint8_t &nlines);
|
||||
extern const char* lcd_display_message_fullscreen_P(const char *msg);
|
||||
@ -162,6 +170,8 @@ enum class FilamentAction : uint_least8_t
|
||||
MmuUnLoad,
|
||||
MmuEject,
|
||||
MmuCut,
|
||||
Preheat,
|
||||
Lay1Cal,
|
||||
};
|
||||
|
||||
extern FilamentAction eFilamentAction;
|
||||
@ -170,7 +180,7 @@ extern bool bFilamentPreheatState;
|
||||
extern bool bFilamentAction;
|
||||
void mFilamentItem(uint16_t nTemp,uint16_t nTempBed);
|
||||
void mFilamentItemForce();
|
||||
void mFilamentMenu();
|
||||
void lcd_generic_preheat_menu();
|
||||
void unload_filament();
|
||||
|
||||
void stack_error();
|
||||
@ -190,7 +200,9 @@ void lcd_wait_for_cool_down();
|
||||
void lcd_extr_cal_reset();
|
||||
|
||||
void lcd_temp_cal_show_result(bool result);
|
||||
#ifdef PINDA_THERMISTOR
|
||||
bool lcd_wait_for_pinda(float temp);
|
||||
#endif //PINDA_THERMISTOR
|
||||
|
||||
|
||||
void bowden_menu();
|
||||
@ -216,22 +228,31 @@ bool lcd_autoDepleteEnabled();
|
||||
//! @brief Wizard state
|
||||
enum class WizState : uint8_t
|
||||
{
|
||||
Run, //!< run wizard? Entry point.
|
||||
Run, //!< run wizard? Main entry point.
|
||||
Restore, //!< restore calibration status
|
||||
Selftest,
|
||||
Selftest, //!< self test
|
||||
Xyz, //!< xyz calibration
|
||||
Z, //!< z calibration
|
||||
IsFil, //!< Is filament loaded? Entry point for 1st layer calibration
|
||||
IsFil, //!< Is filament loaded? First step of 1st layer calibration
|
||||
PreheatPla, //!< waiting for preheat nozzle for PLA
|
||||
Preheat, //!< Preheat for any material
|
||||
Unload, //!< Unload filament
|
||||
LoadFil, //!< Load filament
|
||||
LoadFilCold, //!< Load filament for MMU
|
||||
LoadFilHot, //!< Load filament without MMU
|
||||
IsPla, //!< Is PLA filament?
|
||||
Lay1Cal, //!< First layer calibration
|
||||
Lay1CalCold, //!< First layer calibration, temperature not selected yet
|
||||
Lay1CalHot, //!< First layer calibration, temperature already selected
|
||||
RepeatLay1Cal, //!< Repeat first layer calibration?
|
||||
Finish, //!< Deactivate wizard
|
||||
};
|
||||
|
||||
void lcd_wizard(WizState state);
|
||||
|
||||
#define VOLT_DIV_REF 5
|
||||
#if IR_SENSOR_ANALOG
|
||||
#define IRsensor_Hmin_TRESHOLD (3.0*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~3.0V (0.6*Vcc)
|
||||
#define IRsensor_Lmax_TRESHOLD (1.5*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~1.5V (0.3*Vcc)
|
||||
#define IRsensor_Hopen_TRESHOLD (4.6*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~4.6V (N.C. @ Ru~20-50k, Rd'=56k, Ru'=10k)
|
||||
#define IRsensor_Ldiode_TRESHOLD (0.3*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~0.3V
|
||||
#endif //IR_SENSOR_ANALOG
|
||||
|
||||
#endif //ULTRALCD_H
|
||||
|
@ -27,7 +27,7 @@ const char STR_REVISION_RC [] PROGMEM = "rc";
|
||||
|
||||
inline bool is_whitespace_or_nl(char c)
|
||||
{
|
||||
return c == ' ' || c == '\t' || c == '\n' || c == 'r';
|
||||
return c == ' ' || c == '\t' || c == '\n' || c == '\r';
|
||||
}
|
||||
|
||||
inline bool is_whitespace_or_nl_or_eol(char c)
|
||||
@ -341,13 +341,17 @@ if(oCheckMode==ClCheckMode::_Undef)
|
||||
eeprom_update_byte((uint8_t*)EEPROM_CHECK_MODE,(uint8_t)oCheckMode);
|
||||
}
|
||||
if(farm_mode)
|
||||
{
|
||||
oCheckMode=ClCheckMode::_Strict;
|
||||
if(eeprom_read_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM)==EEPROM_EMPTY_VALUE16)
|
||||
eeprom_update_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM,EEPROM_NOZZLE_DIAMETER_uM_DEFAULT);
|
||||
}
|
||||
oNozzleDiameter=(ClNozzleDiameter)eeprom_read_byte((uint8_t*)EEPROM_NOZZLE_DIAMETER);
|
||||
if((oNozzleDiameter==ClNozzleDiameter::_Diameter_Undef)&& !farm_mode)
|
||||
{
|
||||
oNozzleDiameter=ClNozzleDiameter::_Diameter_400;
|
||||
eeprom_update_byte((uint8_t*)EEPROM_NOZZLE_DIAMETER,(uint8_t)oNozzleDiameter);
|
||||
eeprom_update_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM,400);
|
||||
eeprom_update_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM,EEPROM_NOZZLE_DIAMETER_uM_DEFAULT);
|
||||
}
|
||||
oCheckModel=(ClCheckModel)eeprom_read_byte((uint8_t*)EEPROM_CHECK_MODEL);
|
||||
if(oCheckModel==ClCheckModel::_Undef)
|
||||
@ -401,8 +405,11 @@ lcd_update_enable(true); // display / status-line recovery
|
||||
case ClCheckMode::_Undef:
|
||||
break;
|
||||
}
|
||||
bSettings=false; // flag ('fake parameter') for 'lcd_hw_setup_menu()' function
|
||||
menu_submenu(lcd_hw_setup_menu);
|
||||
if(!farm_mode)
|
||||
{
|
||||
bSettings=false; // flag ('fake parameter') for 'lcd_hw_setup_menu()' function
|
||||
menu_submenu(lcd_hw_setup_menu);
|
||||
}
|
||||
}
|
||||
|
||||
void printer_model_check(uint16_t nPrinterModel)
|
||||
@ -421,13 +428,13 @@ switch(oCheckModel)
|
||||
{
|
||||
case ClCheckModel::_Warn:
|
||||
// lcd_show_fullscreen_message_and_wait_P(_i("Printer model differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("Printer model differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("G-code sliced for a different printer type. Continue?"));
|
||||
lcd_wait_for_click_delay(MSG_PRINT_CHECKING_FAILED_TIMEOUT);
|
||||
//???custom_message_type=CUSTOM_MSG_TYPE_STATUS; // display / status-line recovery
|
||||
lcd_update_enable(true); // display / status-line recovery
|
||||
break;
|
||||
case ClCheckModel::_Strict:
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Printer model differs from the G-code. Please check the value in settings. Print cancelled."));
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."));
|
||||
lcd_print_stop();
|
||||
break;
|
||||
case ClCheckModel::_None:
|
||||
@ -471,13 +478,13 @@ switch(oCheckVersion)
|
||||
{
|
||||
case ClCheckVersion::_Warn:
|
||||
// lcd_show_fullscreen_message_and_wait_P(_i("Printer FW version differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("Printer FW version differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("G-code sliced for a newer firmware. Continue?"));
|
||||
lcd_wait_for_click_delay(MSG_PRINT_CHECKING_FAILED_TIMEOUT);
|
||||
//???custom_message_type=CUSTOM_MSG_TYPE_STATUS; // display / status-line recovery
|
||||
lcd_update_enable(true); // display / status-line recovery
|
||||
break;
|
||||
case ClCheckVersion::_Strict:
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Printer FW version differs from the G-code. Please check the value in settings. Print cancelled."));
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("G-code sliced for a newer firmware. Please update the firmware. Print cancelled."));
|
||||
lcd_print_stop();
|
||||
break;
|
||||
case ClCheckVersion::_None:
|
||||
@ -504,13 +511,13 @@ switch(oCheckGcode)
|
||||
{
|
||||
case ClCheckGcode::_Warn:
|
||||
// lcd_show_fullscreen_message_and_wait_P(_i("Printer G-code level differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("Printer G-code level differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("G-code sliced for a different level. Continue?"));
|
||||
lcd_wait_for_click_delay(MSG_PRINT_CHECKING_FAILED_TIMEOUT);
|
||||
//???custom_message_type=CUSTOM_MSG_TYPE_STATUS; // display / status-line recovery
|
||||
lcd_update_enable(true); // display / status-line recovery
|
||||
break;
|
||||
case ClCheckGcode::_Strict:
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Printer G-code level differs from the G-code. Please check the value in settings. Print cancelled."));
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("G-code sliced for a different level. Please re-slice the model again. Print cancelled."));
|
||||
lcd_print_stop();
|
||||
break;
|
||||
case ClCheckGcode::_None:
|
||||
@ -570,13 +577,13 @@ switch(oCheckModel)
|
||||
{
|
||||
case ClCheckModel::_Warn:
|
||||
// lcd_show_fullscreen_message_and_wait_P(_i("Printer model differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("Printer model differs from the G-code. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_i("G-code sliced for a different printer type. Continue?"));
|
||||
lcd_wait_for_click_delay(MSG_PRINT_CHECKING_FAILED_TIMEOUT);
|
||||
//???custom_message_type=CUSTOM_MSG_TYPE_STATUS; // display / status-line recovery
|
||||
lcd_update_enable(true); // display / status-line recovery
|
||||
break;
|
||||
case ClCheckModel::_Strict:
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("Printer model differs from the G-code. Please check the value in settings. Print cancelled."));
|
||||
lcd_show_fullscreen_message_and_wait_P(_i("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."));
|
||||
lcd_print_stop();
|
||||
break;
|
||||
case ClCheckModel::_None:
|
||||
|
@ -35,6 +35,8 @@ inline void eeprom_update_int8(unsigned char* addr, int8_t v) {
|
||||
|
||||
|
||||
//-//
|
||||
#define EEPROM_NOZZLE_DIAMETER_uM_DEFAULT 400
|
||||
|
||||
enum class ClPrintChecking:uint_least8_t
|
||||
{
|
||||
_Nozzle=1,
|
||||
|
@ -257,7 +257,7 @@ BED SETTINGS
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -324,7 +324,11 @@ PREHEAT SETTINGS
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 55
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
#define ASA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
|
@ -256,7 +256,7 @@ BED SETTINGS
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -319,31 +319,27 @@ PREHEAT SETTINGS
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 80
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 55
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 240
|
||||
#define PET_PREHEAT_HPB_TEMP 90
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 230
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
|
@ -314,7 +314,7 @@
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -377,31 +377,27 @@
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 80
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 230
|
||||
#define PET_PREHEAT_HPB_TEMP 85
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 240
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
|
@ -315,7 +315,7 @@
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -378,31 +378,27 @@
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 80
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 230
|
||||
#define PET_PREHEAT_HPB_TEMP 85
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 240
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
|
@ -314,7 +314,7 @@
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -377,31 +377,27 @@
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 80
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 230
|
||||
#define PET_PREHEAT_HPB_TEMP 85
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 240
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
|
@ -315,7 +315,7 @@
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -378,31 +378,27 @@
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 80
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 230
|
||||
#define PET_PREHEAT_HPB_TEMP 85
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 240
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
|
@ -260,11 +260,13 @@
|
||||
#define TMC2130_SG_THRS_Y 3 // stallguard sensitivity for Y axis
|
||||
#define TMC2130_SG_THRS_Z 4 // stallguard sensitivity for Z axis
|
||||
#define TMC2130_SG_THRS_E 3 // stallguard sensitivity for E axis
|
||||
#define TMC2130_SG_THRS_HOME {3, 3, TMC2130_SG_THRS_Z, TMC2130_SG_THRS_E}
|
||||
|
||||
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||
#define TMC2130_CURRENTS_H {16, 20, 35, 30} // default holding currents for all axes
|
||||
#define TMC2130_CURRENTS_R {16, 20, 35, 30} // default running currents for all axes
|
||||
#define TMC2130_UNLOAD_CURRENT_R 12 // lowe current for M600 to protect filament sensor
|
||||
#define TMC2130_CURRENTS_R_HOME {8, 10, 20, 18} // homing running currents for all axes
|
||||
// #define TMC2130_UNLOAD_CURRENT_R 12 // lower current for M600 to protect filament sensor - Unused
|
||||
|
||||
#define TMC2130_STEALTH_Z
|
||||
|
||||
@ -422,7 +424,7 @@
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -487,31 +489,27 @@
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 80
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 230
|
||||
#define PET_PREHEAT_HPB_TEMP 85
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 240
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
|
@ -262,11 +262,13 @@
|
||||
#define TMC2130_SG_THRS_Y 3 // stallguard sensitivity for Y axis
|
||||
#define TMC2130_SG_THRS_Z 4 // stallguard sensitivity for Z axis
|
||||
#define TMC2130_SG_THRS_E 3 // stallguard sensitivity for E axis
|
||||
#define TMC2130_SG_THRS_HOME {3, 3, TMC2130_SG_THRS_Z, TMC2130_SG_THRS_E}
|
||||
|
||||
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
|
||||
#define TMC2130_CURRENTS_H {16, 20, 35, 30} // default holding currents for all axes
|
||||
#define TMC2130_CURRENTS_R {16, 20, 35, 30} // default running currents for all axes
|
||||
#define TMC2130_UNLOAD_CURRENT_R 12 // lowe current for M600 to protect filament sensor
|
||||
#define TMC2130_CURRENTS_R_HOME {8, 10, 20, 18} // homing running currents for all axes
|
||||
// #define TMC2130_UNLOAD_CURRENT_R 12 // lower current for M600 to protect filament sensor - Unused
|
||||
|
||||
#define TMC2130_STEALTH_Z
|
||||
|
||||
@ -424,7 +426,7 @@
|
||||
#define BED_ADJUSTMENT_UM_MAX 100
|
||||
|
||||
#define MESH_HOME_Z_CALIB 0.2
|
||||
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
|
||||
#define MESH_HOME_Z_SEARCH 5.0f // Z lift for homing, mesh bed leveling etc.
|
||||
|
||||
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
|
||||
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
|
||||
@ -489,31 +491,27 @@
|
||||
|
||||
#define FARM_PREHEAT_HOTEND_TEMP 250
|
||||
#define FARM_PREHEAT_HPB_TEMP 80
|
||||
#define FARM_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
#define ABS_PREHEAT_HOTEND_TEMP 255
|
||||
#define ABS_PREHEAT_HPB_TEMP 100
|
||||
#define ABS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define HIPS_PREHEAT_HOTEND_TEMP 220
|
||||
#define HIPS_PREHEAT_HPB_TEMP 100
|
||||
#define HIPS_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PP_PREHEAT_HOTEND_TEMP 254
|
||||
#define PP_PREHEAT_HPB_TEMP 100
|
||||
#define PP_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PET_PREHEAT_HOTEND_TEMP 230
|
||||
#define PET_PREHEAT_HPB_TEMP 85
|
||||
#define PET_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define FLEX_PREHEAT_HOTEND_TEMP 240
|
||||
#define FLEX_PREHEAT_HPB_TEMP 50
|
||||
#define FLEX_PREHEAT_FAN_SPEED 0
|
||||
|
||||
/*------------------------------------
|
||||
THERMISTORS SETTINGS
|
||||
|
117
PF-build.sh
117
PF-build.sh
@ -56,7 +56,7 @@
|
||||
# Some may argue that this is only used by a script, BUT as soon someone accidentally or on purpose starts Arduino IDE
|
||||
# it will use the default Arduino IDE folders and so can corrupt the build environment.
|
||||
#
|
||||
# Version: 1.0.6-Build_9
|
||||
# Version: 1.0.6-Build_10
|
||||
# Change log:
|
||||
# 12 Jan 2019, 3d-gussner, Fixed "compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections" in 'platform.txt'
|
||||
# 16 Jan 2019, 3d-gussner, Build_2, Added development check to modify 'Configuration.h' to prevent unwanted LCD messages that Firmware is unknown
|
||||
@ -112,7 +112,9 @@
|
||||
# Changed Hex-files folder to PF-build-hex as requested in PR
|
||||
# 23 Jul 2019, 3d-gussner, Added Finding OS version routine so supporting new OS should get easier
|
||||
# 26 Jul 2019, 3d-gussner, Change JSON repository to prusa3d after PR https://github.com/prusa3d/Arduino_Boards/pull/1 was merged
|
||||
|
||||
# 23 Sep 2019, 3d-gussner, Prepare PF-build.sh for comming Prusa3d/Arduino_Boards version 1.0.2 Pull Request
|
||||
# 17 Oct 2019, 3d-gussner, Changed folder and check file names to have seperated build enviroments depening on Arduino IDE version and
|
||||
# board-versions.
|
||||
#### Start check if OSTYPE is supported
|
||||
OS_FOUND=$( command -v uname)
|
||||
|
||||
@ -211,7 +213,8 @@ fi
|
||||
#### Set build environment
|
||||
ARDUINO_ENV="1.8.5"
|
||||
BUILD_ENV="1.0.6"
|
||||
BOARD="PrusaResearchRambo"
|
||||
BOARD="rambo"
|
||||
BOARD_PACKAGE_NAME="PrusaResearchRambo"
|
||||
BOARD_VERSION="1.0.1"
|
||||
BOARD_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json"
|
||||
BOARD_FILENAME="prusa3drambo"
|
||||
@ -229,6 +232,7 @@ echo ""
|
||||
echo "Ardunio IDE :" $ARDUINO_ENV
|
||||
echo "Build env :" $BUILD_ENV
|
||||
echo "Board :" $BOARD
|
||||
echo "Package name:" $BOARD_PACKAGE_NAME
|
||||
echo "Specific Lib:" $LIB
|
||||
echo ""
|
||||
|
||||
@ -259,12 +263,12 @@ if [ $TARGET_OS == "windows" ]; then
|
||||
wget https://downloads.arduino.cc/arduino-$ARDUINO_ENV-windows.zip || exit 7
|
||||
echo "$(tput sgr 0)"
|
||||
fi
|
||||
if [ ! -d "../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor" ]; then
|
||||
if [[ ! -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor" && ! -e "../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt" ]]; then
|
||||
echo "$(tput setaf 6)Unzipping Windows 32/64-bit Arduino IDE portable...$(tput setaf 2)"
|
||||
sleep 2
|
||||
unzip arduino-$ARDUINO_ENV-windows.zip -d ../PF-build-env-$BUILD_ENV || exit 7
|
||||
mv ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor
|
||||
echo "# arduino-$ARDUINO_ENV-$TARGET_OS-$Processor" >> ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV-$TARGET_OS-$Processor
|
||||
mv ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor
|
||||
echo "# arduino-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor" >> ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt
|
||||
echo "$(tput sgr0)"
|
||||
fi
|
||||
fi
|
||||
@ -277,55 +281,55 @@ if [ $TARGET_OS == "linux" ]; then
|
||||
wget --no-check-certificate https://downloads.arduino.cc/arduino-$ARDUINO_ENV-linux$Processor.tar.xz || exit 8
|
||||
echo "$(tput sgr 0)"
|
||||
fi
|
||||
if [[ ! -d "../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor" && ! -e "../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV-$TARGET_OS-$Processor.txt" ]]; then
|
||||
if [[ ! -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor" && ! -e "../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt" ]]; then
|
||||
echo "$(tput setaf 6)Unzipping Linux $Processor Arduino IDE portable...$(tput setaf 2)"
|
||||
sleep 2
|
||||
tar -xvf arduino-$ARDUINO_ENV-linux$Processor.tar.xz -C ../PF-build-env-$BUILD_ENV/ || exit 8
|
||||
mv ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor
|
||||
echo "# arduino-$ARDUINO_ENV-$TARGET_OS-$Processor" >> ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV-$TARGET_OS-$Processor.txt
|
||||
mv ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor
|
||||
echo "# arduino-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor" >> ../PF-build-env-$BUILD_ENV/arduino-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt
|
||||
echo "$(tput sgr0)"
|
||||
fi
|
||||
fi
|
||||
# Make Arduino IDE portable
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/
|
||||
fi
|
||||
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/output/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/output
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/output/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/output
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/sketchbook/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/sketchbook
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/sketchbook/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/sketchbook
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/sketchbook/libraries/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/sketchbook/libraries
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/sketchbook/libraries/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/sketchbook/libraries
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/staging/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/staging
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/staging/ ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/staging
|
||||
fi
|
||||
|
||||
# Change Arduino IDE preferences
|
||||
if [ ! -e ../PF-build-env-$BUILD_ENV/Preferences-$TARGET_OS-$Processor.txt ]; then
|
||||
echo "$(tput setaf 6)Setting $TARGET_OS-$Processor Arduino IDE preferences for portable GUI usage...$(tput setaf 2)"
|
||||
if [ ! -e ../PF-build-env-$BUILD_ENV/Preferences-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt ]; then
|
||||
echo "$(tput setaf 6)Setting $ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor Arduino IDE preferences for portable GUI usage...$(tput setaf 2)"
|
||||
sleep 2
|
||||
echo "update.check"
|
||||
sed -i 's/update.check = true/update.check = false/g' ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/lib/preferences.txt
|
||||
sed -i 's/update.check = true/update.check = false/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "board"
|
||||
sed -i 's/board = uno/board = rambo/g' ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/lib/preferences.txt
|
||||
sed -i 's/board = uno/board = $BOARD/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "editor.linenumbers"
|
||||
sed -i 's/editor.linenumbers = false/editor.linenumbers = true/g' ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/lib/preferences.txt
|
||||
sed -i 's/editor.linenumbers = false/editor.linenumbers = true/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "boardsmanager.additional.urls"
|
||||
echo "boardsmanager.additional.urls=$BOARD_URL" >>../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "build.verbose=true" >>../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "compiler.cache_core=false" >>../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "compiler.warning_level=all" >>../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "# Preferences-$TARGET_OS-$Processor" >> ../PF-build-env-$BUILD_ENV/Preferences-$TARGET_OS-$Processor.txt
|
||||
echo "boardsmanager.additional.urls=$BOARD_URL" >>../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "build.verbose=true" >>../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "compiler.cache_core=false" >>../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "compiler.warning_level=all" >>../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt
|
||||
echo "# Preferences-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor" >> ../PF-build-env-$BUILD_ENV/Preferences-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt
|
||||
echo "$(tput sgr0)"
|
||||
fi
|
||||
|
||||
@ -336,25 +340,26 @@ if [ ! -f "$BOARD_FILENAME-$BOARD_VERSION.tar.bz2" ]; then
|
||||
sleep 2
|
||||
wget $BOARD_FILE_URL || exit 9
|
||||
fi
|
||||
if [[ ! -d "../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD/hardware/avr/$BOARD_VERSION" || ! -e "../PF-build-env-$BUILD_ENV/$BOARD_FILENAME-$BOARD_VERSION-$TARGET_OS-$Processor.txt" ]]; then
|
||||
echo "$(tput setaf 6)Unzipping $BOARD Arduino IDE portable...$(tput setaf 2)"
|
||||
if [[ ! -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME/hardware/avr/$BOARD_VERSION" || ! -e "../PF-build-env-$BUILD_ENV/$BOARD_FILENAME-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt" ]]; then
|
||||
echo "$(tput setaf 6)Unzipping $BOARD_PACKAGE_NAME Arduino IDE portable...$(tput setaf 2)"
|
||||
sleep 2
|
||||
tar -xvf $BOARD_FILENAME-$BOARD_VERSION.tar.bz2 -C ../PF-build-env-$BUILD_ENV/ || exit 10
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD/hardware ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD/hardware
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME/hardware ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME/hardware
|
||||
fi
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD/hardware/avr ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD/hardware/avr
|
||||
if [ ! -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME/hardware/avr ]; then
|
||||
mkdir ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME/hardware/avr
|
||||
fi
|
||||
|
||||
mv ../PF-build-env-$BUILD_ENV/$BOARD_FILENAME-$BOARD_VERSION ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/$BOARD/hardware/avr/$BOARD_VERSION
|
||||
echo "# $BOARD_FILENAME-$BOARD_VERSION" >> ../PF-build-env-$BUILD_ENV/$BOARD_FILENAME-$BOARD_VERSION-$TARGET_OS-$Processor.txt
|
||||
mv ../PF-build-env-$BUILD_ENV/$BOARD_FILENAME-$BOARD_VERSION ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/$BOARD_PACKAGE_NAME/hardware/avr/$BOARD_VERSION
|
||||
echo "# $BOARD_FILENAME-$BOARD_VERSION" >> ../PF-build-env-$BUILD_ENV/$BOARD_FILENAME-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt
|
||||
|
||||
echo "$(tput sgr 0)"
|
||||
fi
|
||||
|
||||
@ -365,30 +370,30 @@ if [ ! -f "PF-build-env-$BUILD_ENV.zip" ]; then
|
||||
wget $PF_BUILD_FILE_URL || exit 11
|
||||
echo "$(tput sgr 0)"
|
||||
fi
|
||||
if [ ! -e "../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$TARGET_OS-$Processor.txt" ]; then
|
||||
if [ ! -e "../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt" ]; then
|
||||
echo "$(tput setaf 6)Unzipping Prusa Firmware build environment...$(tput setaf 2)"
|
||||
sleep 2
|
||||
unzip -o PF-build-env-$BUILD_ENV.zip -d ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor || exit 12
|
||||
echo "# PF-build-env-$TARGET_OS-$Processor-$BUILD_ENV" >> ../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$TARGET_OS-$Processor.txt
|
||||
unzip -o PF-build-env-$BUILD_ENV.zip -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 12
|
||||
echo "# PF-build-env-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor-$BUILD_ENV" >> ../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt
|
||||
echo "$(tput sgr0)"
|
||||
fi
|
||||
|
||||
# Check if User updated Arduino IDE 1.8.5 boardsmanager and tools
|
||||
if [ -d "../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/arduino/tools" ]; then
|
||||
if [ -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/arduino/tools" ]; then
|
||||
echo "$(tput setaf 6)Arduino IDE boards / tools have been manually updated...$"
|
||||
echo "Please don't update the 'Arduino AVR boards' as this will prevent running this script (tput setaf 2)"
|
||||
sleep 2
|
||||
fi
|
||||
if [ -d "../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/arduino/tools/avr-gcc/4.9.2-atmel3.5.4-arduino2" ]; then
|
||||
if [ -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/arduino/tools/avr-gcc/4.9.2-atmel3.5.4-arduino2" ]; then
|
||||
echo "$(tput setaf 6)PrusaReasearch compatible tools have been manually updated...$(tput setaf 2)"
|
||||
sleep 2
|
||||
echo "$(tput setaf 6)Copying Prusa Firmware build environment to manually updated boards / tools...$(tput setaf 2)"
|
||||
sleep 2
|
||||
cp -f ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/hardware/tools/avr/avr/lib/ldscripts/avr6.xn ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/arduino/tools/avr-gcc/4.9.2-atmel3.5.4-arduino2/avr/lib/ldscripts/avr6.xn
|
||||
echo "# PF-build-env-portable-$TARGET_OS-$Processor-$BUILD_ENV" >> ../PF-build-env-$BUILD_ENV/PF-build-env-portable-$BUILD_ENV-$TARGET_OS-$Processor.txt
|
||||
cp -f ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/hardware/tools/avr/avr/lib/ldscripts/avr6.xn ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/arduino/tools/avr-gcc/4.9.2-atmel3.5.4-arduino2/avr/lib/ldscripts/avr6.xn
|
||||
echo "# PF-build-env-portable-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor-$BUILD_ENV" >> ../PF-build-env-$BUILD_ENV/PF-build-env-portable-$BUILD_ENV-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt
|
||||
echo "$(tput sgr0)"
|
||||
fi
|
||||
if [ -d "../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor/portable/packages/arduino/tools/avr-gcc/5.4.0-atmel3.6.1-arduino2" ]; then
|
||||
if [ -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/portable/packages/arduino/tools/avr-gcc/5.4.0-atmel3.6.1-arduino2" ]; then
|
||||
echo "$(tput setaf 1)Arduino IDE tools have been updated manually to a non supported version!!!"
|
||||
echo "Delete ../PF-build-env-$BUILD_ENV and start the script again"
|
||||
echo "Script will not continue until this have been fixed $(tput setaf 2)"
|
||||
@ -489,7 +494,7 @@ if [ ! -z "$3" ] ; then
|
||||
fi
|
||||
|
||||
#Set BUILD_ENV_PATH
|
||||
cd ../PF-build-env-$BUILD_ENV/$TARGET_OS-$Processor || exit 24
|
||||
cd ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 24
|
||||
BUILD_ENV_PATH="$( pwd -P )"
|
||||
|
||||
cd ../..
|
||||
@ -634,8 +639,8 @@ do
|
||||
echo "Start to build Prusa Firmware ..."
|
||||
echo "Using variant $VARIANT$(tput setaf 3)"
|
||||
sleep 2
|
||||
#$BUILD_ENV_PATH/arduino-builder -dump-prefs -debug-level 10 -compile -hardware $ARDUINO/hardware -hardware $ARDUINO/portable/packages -tools $ARDUINO/tools-builder -tools $ARDUINO/hardware/tools/avr -tools $ARDUINO/portable/packages -built-in-libraries $ARDUINO/libraries -libraries $ARDUINO/portable/sketchbook/libraries -fqbn=$BOARD:avr:rambo -ide-version=10805 -build-path=$BUILD_PATH -warnings=all $SCRIPT_PATH/Firmware/Firmware.ino || exit 14
|
||||
$BUILD_ENV_PATH/arduino-builder -compile -hardware $ARDUINO/hardware -hardware $ARDUINO/portable/packages -tools $ARDUINO/tools-builder -tools $ARDUINO/hardware/tools/avr -tools $ARDUINO/portable/packages -built-in-libraries $ARDUINO/libraries -libraries $ARDUINO/portable/sketchbook/libraries -fqbn=$BOARD:avr:rambo -ide-version=10805 -build-path=$BUILD_PATH -warnings=all $SCRIPT_PATH/Firmware/Firmware.ino || exit 14
|
||||
#$BUILD_ENV_PATH/arduino-builder -dump-prefs -debug-level 10 -compile -hardware $ARDUINO/hardware -hardware $ARDUINO/portable/packages -tools $ARDUINO/tools-builder -tools $ARDUINO/hardware/tools/avr -tools $ARDUINO/portable/packages -built-in-libraries $ARDUINO/libraries -libraries $ARDUINO/portable/sketchbook/libraries -fqbn=$BOARD_PACKAGE_NAME:avr:$BOARD -build-path=$BUILD_PATH -warnings=all $SCRIPT_PATH/Firmware/Firmware.ino || exit 14
|
||||
$BUILD_ENV_PATH/arduino-builder -compile -hardware $ARDUINO/hardware -hardware $ARDUINO/portable/packages -tools $ARDUINO/tools-builder -tools $ARDUINO/hardware/tools/avr -tools $ARDUINO/portable/packages -built-in-libraries $ARDUINO/libraries -libraries $ARDUINO/portable/sketchbook/libraries -fqbn=$BOARD_PACKAGE_NAME:avr:$BOARD -build-path=$BUILD_PATH -warnings=all $SCRIPT_PATH/Firmware/Firmware.ino || exit 14
|
||||
echo "$(tput sgr 0)"
|
||||
|
||||
if [ $LANGUAGES == "ALL" ]; then
|
||||
|
15
README.md
15
README.md
@ -111,7 +111,9 @@ Now your Ubuntu subsystem is ready to use the automatic `PF-build.sh` script and
|
||||
- Unix and windows have different line endings (LF vs CRLF), try dos2unix to convert
|
||||
- This should fix the `"$'\r': command not found"` error
|
||||
- to install run `apt-get install dos2unix`
|
||||
|
||||
- If your Windows isn't in English the Paths may look different
|
||||
Example in other languages
|
||||
- English `/mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3` will be on a German Windows`/mnt/c/Anwender/<your-username>/Downloads/Prusa-Firmware-MK3`
|
||||
#### Compile Prusa-firmware with Ubuntu Linux subsystem installed
|
||||
- open Ubuntu bash
|
||||
- change to your source code folder (case sensitive)
|
||||
@ -123,11 +125,14 @@ _notes: Script and instructions contributed by 3d-gussner. Use at your own risk.
|
||||
- Download and install the 64bit Git version https://git-scm.com/download/win
|
||||
- Also follow these instructions https://gist.github.com/evanwill/0207876c3243bbb6863e65ec5dc3f058
|
||||
- Download and install 7z-zip from its official website https://www.7-zip.org/
|
||||
By default, it is installed under the directory /c/Program Files/7-Zip in Windows 10
|
||||
By default, it is installed under the directory /c/Program\ Files/7-Zip in Windows 10
|
||||
- Run `Git-Bash` under Administrator privilege
|
||||
- navigate to the directory /c/Program Files/Git/mingw64/bin
|
||||
- run `ln -s /c/Program Files/7-Zip/7z.exe zip.exe`
|
||||
|
||||
- navigate to the directory /c/Program\ Files/Git/mingw64/bin
|
||||
- run `ln -s /c/Program\ Files/7-Zip/7z.exe zip.exe`
|
||||
- If your Windows isn't in English the Paths may look different
|
||||
Example in other languages
|
||||
- English `/mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3` will be on a German Windows`/mnt/c/Anwender/<your-username>/Downloads/Prusa-Firmware-MK3`
|
||||
- English `ln -s /c/Program\ Files/7-Zip/7z.exe zip.exe` will be on a Spanish Windows `ln -s /c/Archivos\ de\ programa/7-Zip/7z.exe zip.exe`
|
||||
#### Compile Prusa-firmware with Git-bash installed
|
||||
- open Git-bash
|
||||
- change to your source code folder
|
||||
|
@ -198,7 +198,7 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
|
||||
SERIAL_ECHOLN("}");
|
||||
status_number = 15;
|
||||
}
|
||||
else if (isPrintPaused || card.paused)
|
||||
else if (isPrintPaused)
|
||||
{
|
||||
SERIAL_ECHO("{");
|
||||
prusa_stat_printerstatus(14);
|
||||
@ -490,7 +490,7 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
|
||||
{
|
||||
prusa_statistics_case0(15);
|
||||
}
|
||||
else if (isPrintPaused || card.paused)
|
||||
else if (isPrintPaused)
|
||||
{
|
||||
prusa_statistics_case0(14);
|
||||
}
|
||||
@ -753,7 +753,6 @@ TEST_CASE("Prusa_statistics test", "[prusa_stats]")
|
||||
SERIALS_RESET();
|
||||
|
||||
isPrintPaused = 0;
|
||||
card.paused = 0;
|
||||
IS_SD_PRINTING = 1;
|
||||
old_code::prusa_statistics(test_codes[i],0);
|
||||
new_code::prusa_statistics(test_codes[i],0);
|
||||
|
@ -51,7 +51,7 @@ if ! [ -e lang_add.txt ]; then
|
||||
fi
|
||||
|
||||
cat lang_add.txt | sed 's/^/"/;s/$/"/' | while read new_s; do
|
||||
if grep "$new_s" lang_en.txt >/dev/nul; then
|
||||
if grep "$new_s" lang_en.txt >/dev/null; then
|
||||
echo "text already exist:"
|
||||
echo "$new_s"
|
||||
echo
|
||||
|
@ -1,4 +1,4 @@
|
||||
#!/bin/sh
|
||||
#!/bin/bash
|
||||
#
|
||||
# lang-export.sh - multi-language support script
|
||||
# for generating lang_xx.po
|
||||
|
@ -1,10 +1,22 @@
|
||||
#!/bin/sh
|
||||
#!/bin/bash
|
||||
#
|
||||
# lang-import.sh - multi-language support script
|
||||
# for importing translated xx.po
|
||||
|
||||
LNG=$1
|
||||
if [ -z "$LNG" ]; then exit -1; fi
|
||||
# if no arguments, 'all' is selected (all po and also pot will be generated)
|
||||
if [ -z "$LNG" ]; then LNG=all; fi
|
||||
|
||||
# if 'all' is selected, script will generate all po files and also pot file
|
||||
if [ "$LNG" = "all" ]; then
|
||||
./lang-import.sh cz
|
||||
./lang-import.sh de
|
||||
./lang-import.sh es
|
||||
./lang-import.sh fr
|
||||
./lang-import.sh it
|
||||
./lang-import.sh pl
|
||||
exit 0
|
||||
fi
|
||||
|
||||
# language code (iso639-1) is equal to LNG
|
||||
LNGISO=$LNG
|
||||
@ -28,43 +40,51 @@ sed -i 's/ \\n/ /g;s/\\n/ /g' $LNG'_filtered.po'
|
||||
|
||||
#replace in czech translation
|
||||
if [ "$LNG" = "cz" ]; then
|
||||
#replace 'ž' with 'z'
|
||||
#replace 'ž' with 'z'
|
||||
sed -i 's/\xc5\xbe/z/g' $LNG'_filtered.po'
|
||||
#replace 'ì' with 'e'
|
||||
#replace 'ì' with 'e'
|
||||
sed -i 's/\xc4\x9b/e/g' $LNG'_filtered.po'
|
||||
#replace 'í' with 'i'
|
||||
#replace 'í' with 'i'
|
||||
sed -i 's/\xc3\xad/i/g' $LNG'_filtered.po'
|
||||
#replace 'ø' with 'r'
|
||||
#replace 'ø' with 'r'
|
||||
sed -i 's/\xc5\x99/r/g' $LNG'_filtered.po'
|
||||
#replace 'è' with 'c'
|
||||
#replace 'è' with 'c'
|
||||
sed -i 's/\xc4\x8d/c/g' $LNG'_filtered.po'
|
||||
#replace 'á' with 'a'
|
||||
#replace 'á' with 'a'
|
||||
sed -i 's/\xc3\xa1/a/g' $LNG'_filtered.po'
|
||||
#replace 'é' with 'e'
|
||||
#replace 'é' with 'e'
|
||||
sed -i 's/\xc3\xa9/e/g' $LNG'_filtered.po'
|
||||
fi
|
||||
|
||||
#replace in german translation
|
||||
#replace in german translation https://en.wikipedia.org/wiki/German_orthography
|
||||
if [ "$LNG" = "de" ]; then
|
||||
#replace 'ä' with 'ae'
|
||||
#replace 'ä' with 'ae'
|
||||
sed -i 's/\xc3\xa4/ae/g' $LNG'_filtered.po'
|
||||
#replace 'ü' with 'ue'
|
||||
#replace 'Ä' with 'Ae'
|
||||
sed -i 's/\xc3\x84/Ae/g' $LNG'_filtered.po'
|
||||
#replace 'ü' with 'ue'
|
||||
sed -i 's/\xc3\xbc/ue/g' $LNG'_filtered.po'
|
||||
#replace 'ö' with 'oe'
|
||||
#replace 'Ü' with 'Ue'
|
||||
sed -i 's/\xc3\x9c/Ue/g' $LNG'_filtered.po'
|
||||
#replace 'ö' with 'oe'
|
||||
sed -i 's/\xc3\xb6/oe/g' $LNG'_filtered.po'
|
||||
#replace 'Ö' with 'Oe'
|
||||
sed -i 's/\xc3\x96/Oe/g' $LNG'_filtered.po'
|
||||
#replace 'ß' with 'ss'
|
||||
sed -i 's/\xc3\x9f/ss/g' $LNG'_filtered.po'
|
||||
fi
|
||||
|
||||
#replace in spain translation
|
||||
if [ "$LNG" = "es" ]; then
|
||||
#replace 'á' with 'a'
|
||||
#replace 'á' with 'a'
|
||||
sed -i 's/\xc3\xa1/a/g' $LNG'_filtered.po'
|
||||
#replace '?' with '?'
|
||||
#replace '¿' with '?'
|
||||
sed -i 's/\xc2\xbf/?/g' $LNG'_filtered.po'
|
||||
#replace 'ó' with 'o'
|
||||
#replace 'ó' with 'o'
|
||||
sed -i 's/\xc3\xb3/o/g' $LNG'_filtered.po'
|
||||
#replace 'é' with 'e'
|
||||
#replace 'é' with 'e'
|
||||
sed -i 's/\xc3\xa9/e/g' $LNG'_filtered.po'
|
||||
#replace 'í' with 'i'
|
||||
#replace 'í' with 'i'
|
||||
sed -i 's/\xc3\xad/i/g' $LNG'_filtered.po'
|
||||
#replace '!' with '!'
|
||||
sed -i 's/\xc2\xa1/!/g' $LNG'_filtered.po'
|
||||
@ -72,31 +92,39 @@ if [ "$LNG" = "es" ]; then
|
||||
sed -i 's/\xc3\xb1/n/g' $LNG'_filtered.po'
|
||||
fi
|
||||
|
||||
#replace in french translation
|
||||
#replace in french translation https://en.wikipedia.org/wiki/French_orthography
|
||||
if [ "$LNG" = "fr" ]; then
|
||||
#replace 'é' with 'e'
|
||||
sed -i 's/\xc3\xa9/e/g' $LNG'_filtered.po'
|
||||
#replace 'É' with 'E'
|
||||
sed -i 's/\xc3\x89/E/g' $LNG'_filtered.po'
|
||||
#replace 'é' with 'e' (left)
|
||||
sed -i 's/\xc3\xa8/e/g' $LNG'_filtered.po'
|
||||
#replace 'á' with 'a' (left)
|
||||
#replace 'á' with 'a' (right)
|
||||
sed -i 's/\xc3\xa1/a/g' $LNG'_filtered.po'
|
||||
#replace 'Á' with 'A' (right)
|
||||
sed -i 's/\xc3\x81/A/g' $LNG'_filtered.po'
|
||||
#replace 'à' with 'a' (left)
|
||||
sed -i 's/\xc3\xa0/a/g' $LNG'_filtered.po'
|
||||
#replace 'À' with 'A' (left)
|
||||
sed -i 's/\xc3\x80/A/g' $LNG'_filtered.po'
|
||||
#replace 'é' with 'e' (right)
|
||||
sed -i 's/\xc3\xa9/e/g' $LNG'_filtered.po'
|
||||
#replace 'É' with 'E' (right)
|
||||
sed -i 's/\xc3\x89/E/g' $LNG'_filtered.po'
|
||||
#replace 'è' with 'e' (left)
|
||||
sed -i 's/\xc3\xa8/e/g' $LNG'_filtered.po'
|
||||
#replace 'È' with 'E' (left)
|
||||
sed -i 's/\xc3\x88/E/g' $LNG'_filtered.po'
|
||||
fi
|
||||
|
||||
#replace in italian translation
|
||||
if [ "$LNG" = "it" ]; then
|
||||
#replace 'é' with 'e' (left)
|
||||
#replace 'é' with 'e' (left)
|
||||
sed -i 's/\xc3\xa8/e/g' $LNG'_filtered.po'
|
||||
#replace 'á' with 'a' (left)
|
||||
#replace 'á' with 'a' (left)
|
||||
sed -i 's/\xc3\xa0/a/g' $LNG'_filtered.po'
|
||||
#replace 'ó' with 'o' (left)
|
||||
#replace 'ó' with 'o' (left)
|
||||
sed -i 's/\xc3\xb2/o/g' $LNG'_filtered.po'
|
||||
#replace 'ú' with 'u' (left)
|
||||
#replace 'ú' with 'u' (left)
|
||||
sed -i 's/\xc3\xb9/u/g' $LNG'_filtered.po'
|
||||
#replace 'é' with 'e'
|
||||
#replace 'é' with 'e'
|
||||
sed -i 's/\xc3\xa9/e/g' $LNG'_filtered.po'
|
||||
#replace 'É' with 'E' (left)
|
||||
#replace 'É' with 'E' (left)
|
||||
sed -i 's/\xc3\x88/E/g' $LNG'_filtered.po'
|
||||
fi
|
||||
|
||||
|
293
lang/lang_en.txt
293
lang/lang_en.txt
@ -1,3 +1,6 @@
|
||||
#
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
|
||||
@ -34,14 +37,8 @@
|
||||
#MSG_CONFIRM_CARRIAGE_AT_THE_TOP c=20 r=2
|
||||
"Are left and right Z~carriages all up?"
|
||||
|
||||
#MSG_AUTO_DEPLETE_ON c=17 r=1
|
||||
"SpoolJoin [on]"
|
||||
|
||||
#
|
||||
"SpoolJoin [N/A]"
|
||||
|
||||
#MSG_AUTO_DEPLETE_OFF c=17 r=1
|
||||
"SpoolJoin [off]"
|
||||
#MSG_AUTO_DEPLETE c=17 r=1
|
||||
"SpoolJoin"
|
||||
|
||||
#MSG_AUTO_HOME
|
||||
"Auto home"
|
||||
@ -127,14 +124,10 @@
|
||||
#
|
||||
"Copy selected language?"
|
||||
|
||||
#MSG_CRASHDETECT_ON
|
||||
"Crash det. [on]"
|
||||
|
||||
#MSG_CRASHDETECT_NA
|
||||
"Crash det. [N/A]"
|
||||
|
||||
#MSG_CRASHDETECT_OFF
|
||||
"Crash det. [off]"
|
||||
#MSG_CRASHDETECT
|
||||
"Crash det."
|
||||
#
|
||||
"Choose a filament for the First Layer Calibration and select it in the on-screen menu."
|
||||
|
||||
#MSG_CRASH_DETECTED c=20 r=1
|
||||
"Crash detected."
|
||||
@ -166,9 +159,6 @@
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
"Eject filament"
|
||||
|
||||
#
|
||||
"Eject"
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
|
||||
@ -202,14 +192,8 @@
|
||||
#
|
||||
"Fail stats MMU"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_ON c=17 r=1
|
||||
"F. autoload [on]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_NA c=17 r=1
|
||||
"F. autoload [N/A]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_OFF c=17 r=1
|
||||
"F. autoload [off]"
|
||||
#MSG_FSENSOR_AUTOLOAD
|
||||
"F. autoload"
|
||||
|
||||
#
|
||||
"Fail stats"
|
||||
@ -220,20 +204,11 @@
|
||||
#MSG_SELFTEST_FAN c=20
|
||||
"Fan test"
|
||||
|
||||
#MSG_FANS_CHECK_ON c=17 r=1
|
||||
"Fans check [on]"
|
||||
#MSG_FANS_CHECK
|
||||
"Fans check"
|
||||
|
||||
#MSG_FANS_CHECK_OFF c=17 r=1
|
||||
"Fans check [off]"
|
||||
|
||||
#MSG_FSENSOR_ON
|
||||
"Fil. sensor [on]"
|
||||
|
||||
#MSG_FSENSOR_NA
|
||||
"Fil. sensor [N/A]"
|
||||
|
||||
#MSG_FSENSOR_OFF
|
||||
"Fil. sensor [off]"
|
||||
#MSG_FSENSOR
|
||||
"Fil. sensor"
|
||||
|
||||
#
|
||||
"Filam. runouts"
|
||||
@ -346,33 +321,24 @@
|
||||
#MSG_WIZARD_Z_CAL c=20 r=8
|
||||
"I will run z calibration now."
|
||||
|
||||
#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_WATCH
|
||||
"Info screen"
|
||||
|
||||
#
|
||||
"Is filament 1 loaded?"
|
||||
|
||||
#MSG_INSERT_FILAMENT c=20
|
||||
"Insert filament"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
|
||||
#MSG_WIZARD_PLA_FILAMENT c=20 r=2
|
||||
"Is it PLA filament?"
|
||||
|
||||
#MSG_PLA_FILAMENT_LOADED c=20 r=2
|
||||
"Is PLA filament loaded?"
|
||||
|
||||
#MSG_STEEL_SHEET_CHECK c=20 r=2
|
||||
"Is steel sheet on heatbed?"
|
||||
|
||||
#
|
||||
"Last print failures"
|
||||
|
||||
#
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
|
||||
#
|
||||
"Last print"
|
||||
|
||||
@ -439,11 +405,14 @@
|
||||
#MSG_MMU_OK_RESUMING c=20 r=4
|
||||
"MMU OK. Resuming..."
|
||||
|
||||
#MSG_STEALTH_MODE_OFF
|
||||
"Mode [Normal]"
|
||||
#MSG_MODE
|
||||
"Mode"
|
||||
|
||||
#MSG_SILENT_MODE_ON
|
||||
"Mode [silent]"
|
||||
#MSG_NORMAL
|
||||
"Normal"
|
||||
|
||||
#MSG_SILENT
|
||||
"Silent"
|
||||
|
||||
#
|
||||
"MMU needs user attention."
|
||||
@ -451,14 +420,14 @@
|
||||
#
|
||||
"MMU power fails"
|
||||
|
||||
#MSG_STEALTH_MODE_ON
|
||||
"Mode [Stealth]"
|
||||
#MSG_STEALTH
|
||||
"Stealth"
|
||||
|
||||
#MSG_AUTO_MODE_ON
|
||||
"Mode [auto power]"
|
||||
#MSG_AUTO_POWER
|
||||
"Auto power"
|
||||
|
||||
#MSG_SILENT_MODE_OFF
|
||||
"Mode [high power]"
|
||||
#MSG_HIGH_POWER
|
||||
"High power"
|
||||
|
||||
#
|
||||
"MMU2 connected"
|
||||
@ -484,7 +453,7 @@
|
||||
#MSG_NO_CARD
|
||||
"No SD card"
|
||||
|
||||
#
|
||||
#MSG_NA
|
||||
"N/A"
|
||||
|
||||
#MSG_NO
|
||||
@ -547,12 +516,6 @@
|
||||
#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_LOAD_FILAMENT c=20 r=8
|
||||
"Please insert PLA filament to the extruder, then press knob to load it."
|
||||
|
||||
#MSG_PLEASE_LOAD_PLA c=20 r=4
|
||||
"Please load PLA filament first."
|
||||
|
||||
#MSG_CHECK_IDLER c=20 r=4
|
||||
"Please open idler and remove filament manually."
|
||||
|
||||
@ -562,9 +525,6 @@
|
||||
#MSG_PRESS_TO_UNLOAD c=20 r=4
|
||||
"Please press the knob to unload filament"
|
||||
|
||||
#
|
||||
"Please insert PLA filament to the first tube of MMU, then press the knob to load it."
|
||||
|
||||
#MSG_PULL_OUT_FILAMENT c=20 r=4
|
||||
"Please pull out filament immediately"
|
||||
|
||||
@ -634,6 +594,15 @@
|
||||
#
|
||||
"Print FAN"
|
||||
|
||||
#
|
||||
"Please insert filament into the extruder, then press the knob to load it."
|
||||
|
||||
#
|
||||
"Please insert filament into the first tube of the MMU, then press the knob to load it."
|
||||
|
||||
#
|
||||
"Please load filament first."
|
||||
|
||||
#MSG_PRUSA3D
|
||||
"prusa3d.com"
|
||||
|
||||
@ -664,20 +633,17 @@
|
||||
#MSG_BED_CORRECTION_RIGHT c=14 r=1
|
||||
"Right side[um]"
|
||||
|
||||
#MSG_SECOND_SERIAL_ON c=17 r=1
|
||||
"RPi port [on]"
|
||||
|
||||
#MSG_SECOND_SERIAL_OFF c=17 r=1
|
||||
"RPi port [off]"
|
||||
#MSG_RPI_PORT
|
||||
"RPi port"
|
||||
|
||||
#MSG_WIZARD_RERUN c=20 r=7
|
||||
"Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1
|
||||
"SD card [normal]"
|
||||
#MSG_SD_CARD
|
||||
"SD card"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1
|
||||
"SD card [flshAir]"
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY
|
||||
"FlashAir"
|
||||
|
||||
#
|
||||
"Right"
|
||||
@ -709,9 +675,6 @@
|
||||
#
|
||||
"Select nozzle preheat temperature which matches your material."
|
||||
|
||||
#
|
||||
"Select PLA filament:"
|
||||
|
||||
#MSG_SET_TEMPERATURE c=19 r=1
|
||||
"Set temperature:"
|
||||
|
||||
@ -727,38 +690,38 @@
|
||||
#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_SORT_NONE c=17 r=1
|
||||
"Sort [none]"
|
||||
#MSG_SORT
|
||||
"Sort"
|
||||
|
||||
#MSG_SORT_TIME c=17 r=1
|
||||
"Sort [time]"
|
||||
#MSG_NONE
|
||||
"None"
|
||||
|
||||
#MSG_SORT_TIME
|
||||
"Time"
|
||||
|
||||
#
|
||||
"Severe skew"
|
||||
"Severe skew:"
|
||||
|
||||
#MSG_SORT_ALPHA c=17 r=1
|
||||
"Sort [alphabet]"
|
||||
#MSG_SORT_ALPHA
|
||||
"Alphabet"
|
||||
|
||||
#MSG_SORTING c=20 r=1
|
||||
"Sorting files"
|
||||
|
||||
#MSG_SOUND_LOUD c=17 r=1
|
||||
"Sound [loud]"
|
||||
#MSG_SOUND_LOUD
|
||||
"Loud"
|
||||
|
||||
#
|
||||
"Slight skew"
|
||||
"Slight skew:"
|
||||
|
||||
#MSG_SOUND_MUTE c=17 r=1
|
||||
"Sound [mute]"
|
||||
#MSG_SOUND
|
||||
"Sound"
|
||||
|
||||
#
|
||||
"Some problem encountered, Z-leveling enforced ..."
|
||||
|
||||
#MSG_SOUND_ONCE c=17 r=1
|
||||
"Sound [once]"
|
||||
|
||||
#MSG_SOUND_SILENT c=17 r=1
|
||||
"Sound [silent]"
|
||||
#MSG_SOUND_ONCE
|
||||
"Once"
|
||||
|
||||
#MSG_SPEED
|
||||
"Speed"
|
||||
@ -784,14 +747,14 @@
|
||||
#MSG_SELFTEST_SWAPPED
|
||||
"Swapped"
|
||||
|
||||
#MSG_TEMP_CALIBRATION c=20 r=1
|
||||
"Temp. cal. "
|
||||
#
|
||||
"Select filament:"
|
||||
|
||||
#MSG_TEMP_CALIBRATION_ON c=20 r=1
|
||||
"Temp. cal. [on]"
|
||||
#MSG_TEMP_CALIBRATION c=12 r=1
|
||||
"Temp. cal."
|
||||
|
||||
#MSG_TEMP_CALIBRATION_OFF c=20 r=1
|
||||
"Temp. cal. [off]"
|
||||
#
|
||||
"Select temperature which matches your material."
|
||||
|
||||
#MSG_CALIBRATION_PINDA_MENU c=17 r=1
|
||||
"Temp. calibration"
|
||||
@ -925,8 +888,122 @@
|
||||
#
|
||||
"Y distance from min"
|
||||
|
||||
#
|
||||
"The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
|
||||
|
||||
#
|
||||
"Y-correct:"
|
||||
|
||||
#MSG_OFF
|
||||
" [off]"
|
||||
"Off"
|
||||
|
||||
#MSG_ON
|
||||
"On"
|
||||
|
||||
#
|
||||
"Back"
|
||||
|
||||
#
|
||||
"Checks"
|
||||
|
||||
#
|
||||
"False triggering"
|
||||
|
||||
#
|
||||
"FINDA:"
|
||||
|
||||
#MSG_FIRMWARE
|
||||
"Firmware"
|
||||
|
||||
#MSG_STRICT
|
||||
"Strict"
|
||||
|
||||
#MSG_WARN
|
||||
"Warn"
|
||||
|
||||
#
|
||||
"HW Setup"
|
||||
|
||||
#
|
||||
"IR:"
|
||||
|
||||
#MSG_MAGNETS_COMP
|
||||
"Magnets comp."
|
||||
|
||||
#MSG_MESH
|
||||
"Mesh"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
|
||||
#MSG_MMU_MODE
|
||||
"MMU Mode"
|
||||
|
||||
#
|
||||
"Mode change in progress ..."
|
||||
|
||||
#MSG_MODEL
|
||||
"Model"
|
||||
|
||||
#MSG_NOZZLE_DIAMETER
|
||||
"Nozzle d."
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Continue?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Continue?"
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Please update the firmware. Print cancelled."
|
||||
|
||||
#
|
||||
"PINDA:"
|
||||
|
||||
#
|
||||
"Preheating to cut"
|
||||
|
||||
#
|
||||
"Preheating to eject"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Continue?"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
|
||||
|
||||
#
|
||||
"Rename"
|
||||
|
||||
#
|
||||
"Select"
|
||||
|
||||
#
|
||||
"Sensor info"
|
||||
|
||||
#
|
||||
"Sheet"
|
||||
|
||||
#MSG_SOUND_BLIND
|
||||
"Assist"
|
||||
|
||||
#
|
||||
"Steel sheets"
|
||||
|
||||
#
|
||||
"Z-correct:"
|
||||
|
||||
#MSG_Z_PROBE_NR
|
||||
"Z-probe nr."
|
||||
|
@ -1,3 +1,7 @@
|
||||
#
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
"[%.7s]Doladeni Z\x0auz nastaveno, pouzit\x0anebo reset od nuly?\x0a%cPokracovat%cReset"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" z 4"
|
||||
@ -24,7 +28,7 @@
|
||||
|
||||
#MSG_BABYSTEPPING_Z c=15
|
||||
"Adjusting Z:"
|
||||
"Dostavovani Z:"
|
||||
"Doladeni Z:"
|
||||
|
||||
#MSG_SELFTEST_CHECK_ALLCORRECT c=20
|
||||
"All correct "
|
||||
@ -46,18 +50,10 @@
|
||||
"Are left and right Z~carriages all up?"
|
||||
"Dojely oba Z voziky k~hornimu dorazu?"
|
||||
|
||||
#MSG_AUTO_DEPLETE_ON c=17 r=1
|
||||
"SpoolJoin [on]"
|
||||
"SpoolJoin [zap]"
|
||||
|
||||
#
|
||||
"SpoolJoin [N/A]"
|
||||
#MSG_AUTO_DEPLETE c=17 r=1
|
||||
"SpoolJoin"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_DEPLETE_OFF c=17 r=1
|
||||
"SpoolJoin [off]"
|
||||
"SpoolJoin [vyp]"
|
||||
|
||||
#MSG_AUTO_HOME
|
||||
"Auto home"
|
||||
"\x00"
|
||||
@ -68,7 +64,7 @@
|
||||
|
||||
#MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4
|
||||
"Autoloading filament available only when filament sensor is turned on..."
|
||||
"Automaticke zavadeni filamentu je dostupne pouze pri zapnutem filament senzoru..."
|
||||
"Automaticke zavadeni filamentu je mozne pouze pri zapnutem filament senzoru..."
|
||||
|
||||
#MSG_AUTOLOADING_ENABLED c=20 r=4
|
||||
"Autoloading filament is active, just press the knob and insert filament..."
|
||||
@ -92,7 +88,7 @@
|
||||
|
||||
#MSG_BED_HEATING
|
||||
"Bed Heating"
|
||||
"Zahrivani bed"
|
||||
"Zahrivani bedu"
|
||||
|
||||
#MSG_BED_CORRECTION_MENU
|
||||
"Bed level correct"
|
||||
@ -170,17 +166,13 @@
|
||||
"Copy selected language?"
|
||||
"Kopirovat vybrany jazyk?"
|
||||
|
||||
#MSG_CRASHDETECT_ON
|
||||
"Crash det. [on]"
|
||||
"Crash det. [zap]"
|
||||
|
||||
#MSG_CRASHDETECT_NA
|
||||
"Crash det. [N/A]"
|
||||
#MSG_CRASHDETECT
|
||||
"Crash det."
|
||||
"\x00"
|
||||
|
||||
#MSG_CRASHDETECT_OFF
|
||||
"Crash det. [off]"
|
||||
"Crash det. [vyp]"
|
||||
#
|
||||
"Zvolte filament pro kalibraci prvni vrstvy z nasledujiciho menu"
|
||||
"Choose a filament for the First Layer Calibration and select it in the on-screen menu."
|
||||
|
||||
#MSG_CRASH_DETECTED c=20 r=1
|
||||
"Crash detected."
|
||||
@ -222,10 +214,6 @@
|
||||
"Eject filament"
|
||||
"Vysunout filament"
|
||||
|
||||
#
|
||||
"Eject"
|
||||
"Vysunout"
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
"Vysouvam filament"
|
||||
@ -270,17 +258,9 @@
|
||||
"Fail stats MMU"
|
||||
"Selhani MMU"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_ON c=17 r=1
|
||||
"F. autoload [on]"
|
||||
"F. autozav. [zap]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_NA c=17 r=1
|
||||
"F. autoload [N/A]"
|
||||
"F. autozav. [N/A]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_OFF c=17 r=1
|
||||
"F. autoload [off]"
|
||||
"F. autozav. [vyp]"
|
||||
#MSG_FSENSOR_AUTOLOAD
|
||||
"F. autoload"
|
||||
"F. autozav."
|
||||
|
||||
#
|
||||
"Fail stats"
|
||||
@ -294,29 +274,17 @@
|
||||
"Fan test"
|
||||
"Test ventilatoru"
|
||||
|
||||
#MSG_FANS_CHECK_ON c=17 r=1
|
||||
"Fans check [on]"
|
||||
"Kontr. vent.[zap]"
|
||||
#MSG_FANS_CHECK
|
||||
"Fans check"
|
||||
"Kontr. vent."
|
||||
|
||||
#MSG_FANS_CHECK_OFF c=17 r=1
|
||||
"Fans check [off]"
|
||||
"Kontr. vent.[vyp]"
|
||||
|
||||
#MSG_FSENSOR_ON
|
||||
"Fil. sensor [on]"
|
||||
"Fil. senzor [zap]"
|
||||
|
||||
#MSG_FSENSOR_NA
|
||||
"Fil. sensor [N/A]"
|
||||
"Fil. senzor [N/A]"
|
||||
|
||||
#MSG_FSENSOR_OFF
|
||||
"Fil. sensor [off]"
|
||||
"Fil. senzor [vyp]"
|
||||
#MSG_FSENSOR
|
||||
"Fil. sensor"
|
||||
"Fil. senzor"
|
||||
|
||||
#
|
||||
"Filam. runouts"
|
||||
"Vypadky filamentu"
|
||||
"Vypadky filam."
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
@ -462,18 +430,10 @@
|
||||
"I will run z calibration now."
|
||||
"Nyni provedu z kalibraci."
|
||||
|
||||
#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."
|
||||
"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_WATCH
|
||||
"Info screen"
|
||||
"Informace"
|
||||
|
||||
#
|
||||
"Is filament 1 loaded?"
|
||||
"Je filament 1 zaveden?"
|
||||
|
||||
#MSG_INSERT_FILAMENT c=20
|
||||
"Insert filament"
|
||||
"Vlozte filament"
|
||||
@ -482,14 +442,6 @@
|
||||
"Is filament loaded?"
|
||||
"Je filament zaveden?"
|
||||
|
||||
#MSG_WIZARD_PLA_FILAMENT c=20 r=2
|
||||
"Is it PLA filament?"
|
||||
"Je to PLA filament?"
|
||||
|
||||
#MSG_PLA_FILAMENT_LOADED c=20 r=2
|
||||
"Is PLA filament loaded?"
|
||||
"Je PLA filament zaveden?"
|
||||
|
||||
#MSG_STEEL_SHEET_CHECK c=20 r=2
|
||||
"Is steel sheet on heatbed?"
|
||||
"Je tiskovy plat na podlozce?"
|
||||
@ -498,6 +450,10 @@
|
||||
"Last print failures"
|
||||
"Selhani posl. tisku"
|
||||
|
||||
#
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
"Mate-li vice tiskovych platu, kalibrujte je v menu Nastaveni - HW nastaveni - Tiskove platy"
|
||||
|
||||
#
|
||||
"Last print"
|
||||
"Posledni tisk"
|
||||
@ -508,7 +464,7 @@
|
||||
|
||||
#
|
||||
"Left"
|
||||
"Vlevo:"
|
||||
"Vlevo"
|
||||
|
||||
#MSG_BED_CORRECTION_LEFT c=14 r=1
|
||||
"Left side [um]"
|
||||
@ -586,13 +542,17 @@
|
||||
"MMU OK. Resuming..."
|
||||
"MMU OK. Pokracuji..."
|
||||
|
||||
#MSG_STEALTH_MODE_OFF
|
||||
"Mode [Normal]"
|
||||
"Mod [Normal]"
|
||||
#MSG_MODE
|
||||
"Mode"
|
||||
"Mod"
|
||||
|
||||
#MSG_SILENT_MODE_ON
|
||||
"Mode [silent]"
|
||||
"Mod [tichy]"
|
||||
#MSG_NORMAL
|
||||
"Normal"
|
||||
"\x00"
|
||||
|
||||
#MSG_SILENT
|
||||
"Silent"
|
||||
"Tichy"
|
||||
|
||||
#
|
||||
"MMU needs user attention."
|
||||
@ -602,17 +562,17 @@
|
||||
"MMU power fails"
|
||||
"MMU vypadky proudu"
|
||||
|
||||
#MSG_STEALTH_MODE_ON
|
||||
"Mode [Stealth]"
|
||||
"Mod [tichy]"
|
||||
#MSG_STEALTH
|
||||
"Stealth"
|
||||
"Tichy"
|
||||
|
||||
#MSG_AUTO_MODE_ON
|
||||
"Mode [auto power]"
|
||||
"Mod [automaticky]"
|
||||
#MSG_AUTO_POWER
|
||||
"Auto power"
|
||||
"Automaticky"
|
||||
|
||||
#MSG_SILENT_MODE_OFF
|
||||
"Mode [high power]"
|
||||
"Mod [vys. vykon]"
|
||||
#MSG_HIGH_POWER
|
||||
"High power"
|
||||
"Vys. vykon"
|
||||
|
||||
#
|
||||
"MMU2 connected"
|
||||
@ -646,7 +606,7 @@
|
||||
"No SD card"
|
||||
"Zadna SD karta"
|
||||
|
||||
#
|
||||
#MSG_NA
|
||||
"N/A"
|
||||
"\x00"
|
||||
|
||||
@ -688,7 +648,7 @@
|
||||
|
||||
#
|
||||
"Nozzle FAN"
|
||||
"Trysk. vent."
|
||||
"Vent. trysky"
|
||||
|
||||
#MSG_PAUSE_PRINT
|
||||
"Pause print"
|
||||
@ -730,14 +690,6 @@
|
||||
"Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
"Prosim nahlednete do prirucky 3D tiskare a opravte problem. Pote obnovte Pruvodce restartovanim tiskarny."
|
||||
|
||||
#MSG_WIZARD_LOAD_FILAMENT c=20 r=8
|
||||
"Please insert PLA filament to the extruder, then press knob to load it."
|
||||
"Prosim vlozte PLA filament do extruderu, pote stisknete tlacitko pro zavedeni filamentu."
|
||||
|
||||
#MSG_PLEASE_LOAD_PLA c=20 r=4
|
||||
"Please load PLA filament first."
|
||||
"Nejdrive prosim zavedte PLA filament."
|
||||
|
||||
#MSG_CHECK_IDLER c=20 r=4
|
||||
"Please open idler and remove filament manually."
|
||||
"Prosim otevrete idler a manualne odstrante filament."
|
||||
@ -750,10 +702,6 @@
|
||||
"Please press the knob to unload filament"
|
||||
"Pro vysunuti filamentu stisknete prosim tlacitko"
|
||||
|
||||
#
|
||||
"Please insert PLA filament to the first tube of MMU, then press the knob to load it."
|
||||
"Prosim vlozte PLA filament do trubicky MMU, pote stisknete tlacitko pro zavedeni filamentu."
|
||||
|
||||
#MSG_PULL_OUT_FILAMENT c=20 r=4
|
||||
"Please pull out filament immediately"
|
||||
"Prosim vyjmete urychlene filament"
|
||||
@ -792,7 +740,7 @@
|
||||
|
||||
#MSG_WIZARD_HEATING c=20 r=3
|
||||
"Preheating nozzle. Please wait."
|
||||
"Predehrivam trysku. Prosim cekejte."
|
||||
"Predehrev trysky. Prosim cekejte."
|
||||
|
||||
#
|
||||
"Please upgrade."
|
||||
@ -812,11 +760,11 @@
|
||||
|
||||
#
|
||||
"Preheating to load"
|
||||
"Predehrivam k zavedeni"
|
||||
"Predehrev k zavedeni"
|
||||
|
||||
#
|
||||
"Preheating to unload"
|
||||
"Predehrivam k vyjmuti"
|
||||
"Predehrev k vyjmuti"
|
||||
|
||||
#MSG_SELFTEST_PRINT_FAN_SPEED c=18
|
||||
"Print fan:"
|
||||
@ -828,7 +776,7 @@
|
||||
|
||||
#
|
||||
"Press the knob"
|
||||
"Stisknete tlacitko"
|
||||
"Stisknete hl. tlacitko"
|
||||
|
||||
#MSG_PRINT_PAUSED c=20 r=1
|
||||
"Print paused"
|
||||
@ -846,6 +794,18 @@
|
||||
"Print FAN"
|
||||
"Tiskovy vent."
|
||||
|
||||
#
|
||||
"Please insert filament into the extruder, then press the knob to load it."
|
||||
"Prosim vlozte filament do extruderu a stisknete tlacitko k jeho zavedeni"
|
||||
|
||||
#
|
||||
"Please insert filament into the first tube of the MMU, then press the knob to load it."
|
||||
"Prosim vlozte filament do prvni trubicky MMU a stisknete tlacitko k jeho zavedeni"
|
||||
|
||||
#
|
||||
"Please load filament first."
|
||||
"Prosim nejdriv zavedte filament"
|
||||
|
||||
#MSG_PRUSA3D
|
||||
"prusa3d.com"
|
||||
"\x00"
|
||||
@ -886,25 +846,21 @@
|
||||
"Right side[um]"
|
||||
"Vpravo [um]"
|
||||
|
||||
#MSG_SECOND_SERIAL_ON c=17 r=1
|
||||
"RPi port [on]"
|
||||
"RPi port [zap]"
|
||||
|
||||
#MSG_SECOND_SERIAL_OFF c=17 r=1
|
||||
"RPi port [off]"
|
||||
"RPi port [vyp]"
|
||||
#MSG_RPI_PORT
|
||||
"RPi port"
|
||||
"\x00"
|
||||
|
||||
#MSG_WIZARD_RERUN c=20 r=7
|
||||
"Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
"Spusteni Pruvodce vymaze ulozene vysledky vsech kalibraci a spusti kalibracni proces od zacatku. Pokracovat?"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1
|
||||
"SD card [normal]"
|
||||
#MSG_SD_CARD
|
||||
"SD card"
|
||||
"\x00"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1
|
||||
"SD card [flshAir]"
|
||||
"SD card [FlshAir]"
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY
|
||||
"FlashAir"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Right"
|
||||
@ -946,10 +902,6 @@
|
||||
"Select nozzle preheat temperature which matches your material."
|
||||
"Vyberte teplotu predehrati trysky ktera odpovida vasemu materialu."
|
||||
|
||||
#
|
||||
"Select PLA filament:"
|
||||
"Vyberte PLA filament:"
|
||||
|
||||
#MSG_SET_TEMPERATURE c=19 r=1
|
||||
"Set temperature:"
|
||||
"Nastavte teplotu:"
|
||||
@ -970,49 +922,49 @@
|
||||
"Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
|
||||
"Nektere soubory nebudou setrideny. Maximalni pocet souboru ve slozce pro setrideni je 100."
|
||||
|
||||
#MSG_SORT_NONE c=17 r=1
|
||||
"Sort [none]"
|
||||
"Trideni [Zadne]"
|
||||
#MSG_SORT
|
||||
"Sort"
|
||||
"Trideni"
|
||||
|
||||
#MSG_SORT_TIME c=17 r=1
|
||||
"Sort [time]"
|
||||
"Trideni [cas]"
|
||||
#MSG_NONE
|
||||
"None"
|
||||
"Zadne"
|
||||
|
||||
#MSG_SORT_TIME
|
||||
"Time"
|
||||
"Cas"
|
||||
|
||||
#
|
||||
"Severe skew"
|
||||
"Tezke zkoseni"
|
||||
"Severe skew:"
|
||||
"Tezke zkoseni:"
|
||||
|
||||
#MSG_SORT_ALPHA c=17 r=1
|
||||
"Sort [alphabet]"
|
||||
"Trideni [Abeceda]"
|
||||
#MSG_SORT_ALPHA
|
||||
"Alphabet"
|
||||
"Abeceda"
|
||||
|
||||
#MSG_SORTING c=20 r=1
|
||||
"Sorting files"
|
||||
"Trideni souboru"
|
||||
|
||||
#MSG_SOUND_LOUD c=17 r=1
|
||||
"Sound [loud]"
|
||||
"Zvuk [hlasity]"
|
||||
#MSG_SOUND_LOUD
|
||||
"Loud"
|
||||
"Hlasity"
|
||||
|
||||
#
|
||||
"Slight skew"
|
||||
"Lehke zkoseni"
|
||||
"Slight skew:"
|
||||
"Lehke zkoseni:"
|
||||
|
||||
#MSG_SOUND_MUTE c=17 r=1
|
||||
"Sound [mute]"
|
||||
"Zvuk [vypnuto]"
|
||||
#MSG_SOUND
|
||||
"Sound"
|
||||
"Zvuk"
|
||||
|
||||
#
|
||||
"Some problem encountered, Z-leveling enforced ..."
|
||||
"Vyskytl se problem, srovnavam osu Z ..."
|
||||
|
||||
#MSG_SOUND_ONCE c=17 r=1
|
||||
"Sound [once]"
|
||||
"Zvuk [jednou]"
|
||||
|
||||
#MSG_SOUND_SILENT c=17 r=1
|
||||
"Sound [silent]"
|
||||
"Zvuk [tichy]"
|
||||
#MSG_SOUND_ONCE
|
||||
"Once"
|
||||
"Jednou"
|
||||
|
||||
#MSG_SPEED
|
||||
"Speed"
|
||||
@ -1046,17 +998,17 @@
|
||||
"Swapped"
|
||||
"Prohozene"
|
||||
|
||||
#MSG_TEMP_CALIBRATION c=20 r=1
|
||||
"Temp. cal. "
|
||||
"Tepl. kal. "
|
||||
#
|
||||
"Select filament:"
|
||||
"Zvolte filament:"
|
||||
|
||||
#MSG_TEMP_CALIBRATION_ON c=20 r=1
|
||||
"Temp. cal. [on]"
|
||||
"Tepl. kal. [zap]"
|
||||
#MSG_TEMP_CALIBRATION c=12 r=1
|
||||
"Temp. cal."
|
||||
"Tepl. kal."
|
||||
|
||||
#MSG_TEMP_CALIBRATION_OFF c=20 r=1
|
||||
"Temp. cal. [off]"
|
||||
"Tepl. kal. [vyp]"
|
||||
#
|
||||
"Select temperature which matches your material."
|
||||
"Zvolte teplotu, ktera odpovida vasemu materialu."
|
||||
|
||||
#MSG_CALIBRATION_PINDA_MENU c=17 r=1
|
||||
"Temp. calibration"
|
||||
@ -1234,10 +1186,162 @@
|
||||
"Y distance from min"
|
||||
"Y vzdalenost od min"
|
||||
|
||||
#
|
||||
"The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Y-correct:"
|
||||
"Korekce Y:"
|
||||
|
||||
#MSG_OFF
|
||||
" [off]"
|
||||
"Off"
|
||||
"Vyp"
|
||||
|
||||
#MSG_ON
|
||||
"On"
|
||||
"Zap"
|
||||
|
||||
#
|
||||
"Back"
|
||||
"Zpet"
|
||||
|
||||
#
|
||||
"Checks"
|
||||
"Kontrola"
|
||||
|
||||
#
|
||||
"False triggering"
|
||||
"Falesne spusteni"
|
||||
|
||||
#
|
||||
"FINDA:"
|
||||
"\x00"
|
||||
|
||||
#MSG_FIRMWARE
|
||||
"Firmware"
|
||||
"\x00"
|
||||
|
||||
#MSG_STRICT
|
||||
"Strict"
|
||||
"Prisne"
|
||||
|
||||
#MSG_WARN
|
||||
"Warn"
|
||||
"Varovat"
|
||||
|
||||
#
|
||||
"HW Setup"
|
||||
"HW nastaveni"
|
||||
|
||||
#
|
||||
"IR:"
|
||||
"\x00"
|
||||
|
||||
#MSG_MAGNETS_COMP
|
||||
"Magnets comp."
|
||||
"Komp. magnetu"
|
||||
|
||||
#MSG_MESH
|
||||
"Mesh"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Mesh Bed Leveling"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"MK3S firmware detekovan na tiskarne MK3"
|
||||
|
||||
#MSG_MMU_MODE
|
||||
"MMU Mode"
|
||||
"MMU mod"
|
||||
|
||||
#
|
||||
"Mode change in progress ..."
|
||||
"Probiha zmena modu..."
|
||||
|
||||
#MSG_MODEL
|
||||
"Model"
|
||||
"\x00"
|
||||
|
||||
#MSG_NOZZLE_DIAMETER
|
||||
"Nozzle d."
|
||||
"Tryska"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Continue?"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-code je pripraven pro jiny typ tiskarny. Pokracovat?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
"G-code je pripraven pro jiny typ tiskarny. Prosim preslicujte model znovu. Tisk zrusen."
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Continue?"
|
||||
"G-code je pripraven pro novejsi firmware. Pokracovat?"
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Please update the firmware. Print cancelled."
|
||||
"G-code je pripraven pro novejsi firmware. Prosim aktualizujte firmware. Tisk zrusen."
|
||||
|
||||
#
|
||||
"PINDA:"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Preheating to cut"
|
||||
"Predehrev k ustrizeni"
|
||||
|
||||
#
|
||||
"Preheating to eject"
|
||||
"Predehrev k vysunuti"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Continue?"
|
||||
"Prumer trysky tiskarny se lisi od G-code. Pokracovat?"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
|
||||
"Prumer trysky tiskarny se lisi od G-code. Prosim zkontrolujte nastaveni. Tisk zrusen."
|
||||
|
||||
#
|
||||
"Rename"
|
||||
"Prejmenovat"
|
||||
|
||||
#
|
||||
"Select"
|
||||
"Vybrat"
|
||||
|
||||
#
|
||||
"Sensor info"
|
||||
"Senzor info"
|
||||
|
||||
#
|
||||
"Sheet"
|
||||
"Plat"
|
||||
|
||||
#MSG_SOUND_BLIND
|
||||
"Assist"
|
||||
"Asist."
|
||||
|
||||
#
|
||||
"Steel sheets"
|
||||
"Tiskove platy"
|
||||
|
||||
#
|
||||
"Z-correct:"
|
||||
"Korekce Z:"
|
||||
|
||||
#MSG_Z_PROBE_NR
|
||||
"Z-probe nr."
|
||||
"Pocet mereni Z"
|
||||
|
@ -1,3 +1,7 @@
|
||||
#
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
"[%.7s]Z Einstell.\x0aWert gesetzt,weiter\x0aoder mit 0 beginnen?\x0a%cWeiter%cNeu beginnen"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" von 4"
|
||||
@ -24,11 +28,11 @@
|
||||
|
||||
#MSG_BABYSTEPPING_Z c=15
|
||||
"Adjusting Z:"
|
||||
"Z Einstellung:"
|
||||
"Z Anpassen:"
|
||||
|
||||
#MSG_SELFTEST_CHECK_ALLCORRECT c=20
|
||||
"All correct "
|
||||
"Alles richtig "
|
||||
"Alles richtig "
|
||||
|
||||
#MSG_WIZARD_DONE c=20 r=8
|
||||
"All is done. Happy printing!"
|
||||
@ -46,17 +50,9 @@
|
||||
"Are left and right Z~carriages all up?"
|
||||
"Sind linke+rechte Z- Schlitten ganz oben?"
|
||||
|
||||
#MSG_AUTO_DEPLETE_ON c=17 r=1
|
||||
"SpoolJoin [on]"
|
||||
"SpoolJoin [an]"
|
||||
|
||||
#
|
||||
"SpoolJoin [N/A]"
|
||||
"SpoolJoin [N/V]"
|
||||
|
||||
#MSG_AUTO_DEPLETE_OFF c=17 r=1
|
||||
"SpoolJoin [off]"
|
||||
"SpoolJoin [aus]"
|
||||
#MSG_AUTO_DEPLETE c=17 r=1
|
||||
"SpoolJoin"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_HOME
|
||||
"Auto home"
|
||||
@ -64,11 +60,11 @@
|
||||
|
||||
#MSG_AUTOLOAD_FILAMENT c=17
|
||||
"AutoLoad filament"
|
||||
"Auto-Laden Filament"
|
||||
"AutoLaden Filament"
|
||||
|
||||
#MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4
|
||||
"Autoloading filament available only when filament sensor is turned on..."
|
||||
"Automatisches Laden Filament nur bei einge schaltetem Filament- sensor verfuegbar..."
|
||||
"Automatisches Laden Filament nur bei eingeschaltetem Fil. sensor verfuegbar..."
|
||||
|
||||
#MSG_AUTOLOADING_ENABLED c=20 r=4
|
||||
"Autoloading filament is active, just press the knob and insert filament..."
|
||||
@ -170,17 +166,13 @@
|
||||
"Copy selected language?"
|
||||
"Gewaehlte Sprache kopieren?"
|
||||
|
||||
#MSG_CRASHDETECT_ON
|
||||
"Crash det. [on]"
|
||||
"Crash Erk. [an]"
|
||||
#MSG_CRASHDETECT
|
||||
"Crash det."
|
||||
"Crash Erk."
|
||||
|
||||
#MSG_CRASHDETECT_NA
|
||||
"Crash det. [N/A]"
|
||||
"Crash Erk. [nv]"
|
||||
|
||||
#MSG_CRASHDETECT_OFF
|
||||
"Crash det. [off]"
|
||||
"Crash Erk. [aus]"
|
||||
#
|
||||
"Choose a filament for the First Layer Calibration and select it in the on-screen menu."
|
||||
"Waehlen Sie ein Filament fuer Erste Schichtkalibrierung aus und waehlen Sie es im On-Screen-Menu aus."
|
||||
|
||||
#MSG_CRASH_DETECTED c=20 r=1
|
||||
"Crash detected."
|
||||
@ -222,10 +214,6 @@
|
||||
"Eject filament"
|
||||
"Filamentauswurf"
|
||||
|
||||
#
|
||||
"Eject"
|
||||
"Auswurf"
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
"werfe Filament aus"
|
||||
@ -270,17 +258,9 @@
|
||||
"Fail stats MMU"
|
||||
"MMU-Fehler"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_ON c=17 r=1
|
||||
"F. autoload [on]"
|
||||
"F.Autoladen [an]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_NA c=17 r=1
|
||||
"F. autoload [N/A]"
|
||||
"F. Autoload [nv]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_OFF c=17 r=1
|
||||
"F. autoload [off]"
|
||||
"F. Autoload [aus]"
|
||||
#MSG_FSENSOR_AUTOLOAD
|
||||
"F. autoload"
|
||||
"F. autoladen"
|
||||
|
||||
#
|
||||
"Fail stats"
|
||||
@ -294,25 +274,13 @@
|
||||
"Fan test"
|
||||
"Lueftertest"
|
||||
|
||||
#MSG_FANS_CHECK_ON c=17 r=1
|
||||
"Fans check [on]"
|
||||
"Luefter Chk. [an]"
|
||||
#MSG_FANS_CHECK
|
||||
"Fans check"
|
||||
"Luefter Chk."
|
||||
|
||||
#MSG_FANS_CHECK_OFF c=17 r=1
|
||||
"Fans check [off]"
|
||||
"Luefter Chk.[aus]"
|
||||
|
||||
#MSG_FSENSOR_ON
|
||||
"Fil. sensor [on]"
|
||||
"Fil. Sensor [an]"
|
||||
|
||||
#MSG_FSENSOR_NA
|
||||
"Fil. sensor [N/A]"
|
||||
"Fil. Sensor [nv]"
|
||||
|
||||
#MSG_FSENSOR_OFF
|
||||
"Fil. sensor [off]"
|
||||
"Fil. Sensor [aus]"
|
||||
#MSG_FSENSOR
|
||||
"Fil. sensor"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Filam. runouts"
|
||||
@ -320,7 +288,7 @@
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
"Filament extrudiert + richtige Farbe?"
|
||||
"Filament extrudiert mit richtiger Farbe?"
|
||||
|
||||
#MSG_NOT_LOADED c=19
|
||||
"Filament not loaded"
|
||||
@ -462,18 +430,10 @@
|
||||
"I will run z calibration now."
|
||||
"Ich werde jetzt die Z Kalibrierung durchfuehren."
|
||||
|
||||
#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."
|
||||
"Ich werde jetzt eine Linie drucken. Waehrend des Druckes koennen Sie die Duese allmaehlich senken, indem Sie den Knopf drehen, bis Sie die optimale Hoehe erreichen. Sehen Sie sich die Bilder in unserem Handbuch im Kapitel Kalibrierung an."
|
||||
|
||||
#MSG_WATCH
|
||||
"Info screen"
|
||||
"Infoanzeige"
|
||||
|
||||
#
|
||||
"Is filament 1 loaded?"
|
||||
"Wurde Filament 1 geladen?"
|
||||
|
||||
#MSG_INSERT_FILAMENT c=20
|
||||
"Insert filament"
|
||||
"Filament einlegen"
|
||||
@ -482,14 +442,6 @@
|
||||
"Is filament loaded?"
|
||||
"Ist das Filament geladen?"
|
||||
|
||||
#MSG_WIZARD_PLA_FILAMENT c=20 r=2
|
||||
"Is it PLA filament?"
|
||||
"Ist es wirklich PLA Filament?"
|
||||
|
||||
#MSG_PLA_FILAMENT_LOADED c=20 r=2
|
||||
"Is PLA filament loaded?"
|
||||
"Ist PLA Filament geladen?"
|
||||
|
||||
#MSG_STEEL_SHEET_CHECK c=20 r=2
|
||||
"Is steel sheet on heatbed?"
|
||||
"Liegt das Stahlblech auf dem Heizbett?"
|
||||
@ -498,6 +450,10 @@
|
||||
"Last print failures"
|
||||
"Letzte Druckfehler"
|
||||
|
||||
#
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
"Wenn Sie zusaetzliche Stahlbleche haben, kalibrieren Sie deren Voreinstellungen unter Einstellungen - HW Setup - Stahlbleche."
|
||||
|
||||
#
|
||||
"Last print"
|
||||
"Letzter Druck"
|
||||
@ -556,11 +512,11 @@
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
"Mesh Bed Leveling"
|
||||
"Mesh Bett Ausgleich"
|
||||
"MeshBett Ausgleich"
|
||||
|
||||
#MSG_MMU_OK_RESUMING_POSITION c=20 r=4
|
||||
"MMU OK. Resuming position..."
|
||||
"MMU OK. Position wiederherstellen... "
|
||||
"MMU OK. Position wiederherstellen..."
|
||||
|
||||
#MSG_MMU_OK_RESUMING_TEMPERATURE c=20 r=4
|
||||
"MMU OK. Resuming temperature..."
|
||||
@ -586,13 +542,17 @@
|
||||
"MMU OK. Resuming..."
|
||||
"MMU OK. Weiterdrucken..."
|
||||
|
||||
#MSG_STEALTH_MODE_OFF
|
||||
"Mode [Normal]"
|
||||
"Modus [Normal]"
|
||||
#MSG_MODE
|
||||
"Mode"
|
||||
"Modus"
|
||||
|
||||
#MSG_SILENT_MODE_ON
|
||||
"Mode [silent]"
|
||||
"Modus [leise]"
|
||||
#MSG_NORMAL
|
||||
"Normal"
|
||||
"\x00"
|
||||
|
||||
#MSG_SILENT
|
||||
"Silent"
|
||||
"Leise"
|
||||
|
||||
#
|
||||
"MMU needs user attention."
|
||||
@ -602,17 +562,17 @@
|
||||
"MMU power fails"
|
||||
"MMU Netzfehler"
|
||||
|
||||
#MSG_STEALTH_MODE_ON
|
||||
"Mode [Stealth]"
|
||||
"Modus [Stealth]"
|
||||
#MSG_STEALTH
|
||||
"Stealth"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_MODE_ON
|
||||
"Mode [auto power]"
|
||||
"Modus[Auto Power]"
|
||||
#MSG_AUTO_POWER
|
||||
"Auto power"
|
||||
"\x00"
|
||||
|
||||
#MSG_SILENT_MODE_OFF
|
||||
"Mode [high power]"
|
||||
"Modus[Hohe Leist]"
|
||||
#MSG_HIGH_POWER
|
||||
"High power"
|
||||
"Hohe leist"
|
||||
|
||||
#
|
||||
"MMU2 connected"
|
||||
@ -646,9 +606,9 @@
|
||||
"No SD card"
|
||||
"Keine SD Karte"
|
||||
|
||||
#
|
||||
#MSG_NA
|
||||
"N/A"
|
||||
"N.V."
|
||||
"N/V"
|
||||
|
||||
#MSG_NO
|
||||
"No"
|
||||
@ -688,7 +648,7 @@
|
||||
|
||||
#
|
||||
"Nozzle FAN"
|
||||
"Duesen Luefter"
|
||||
"Duesevent."
|
||||
|
||||
#MSG_PAUSE_PRINT
|
||||
"Pause print"
|
||||
@ -730,14 +690,6 @@
|
||||
"Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
"Bitte lesen Sie unser Handbuch und beheben Sie das Problem. Fahren Sie dann mit dem Assistenten fort, indem Sie den Drucker neu starten."
|
||||
|
||||
#MSG_WIZARD_LOAD_FILAMENT c=20 r=8
|
||||
"Please insert PLA filament to the extruder, then press knob to load it."
|
||||
"Legen Sie bitte PLA Filament in den Extruder und druecken Sie den Knopf, um es zu laden."
|
||||
|
||||
#MSG_PLEASE_LOAD_PLA c=20 r=4
|
||||
"Please load PLA filament first."
|
||||
"Bitte laden Sie zuerst PLA Filament."
|
||||
|
||||
#MSG_CHECK_IDLER c=20 r=4
|
||||
"Please open idler and remove filament manually."
|
||||
"Bitte Spannrolle oeffnen und Fila- ment von Hand entfernen"
|
||||
@ -750,10 +702,6 @@
|
||||
"Please press the knob to unload filament"
|
||||
"Bitte druecken Sie den Knopf um das Filament zu entladen."
|
||||
|
||||
#
|
||||
"Please insert PLA filament to the first tube of MMU, then press the knob to load it."
|
||||
"Legen Sie bitte PLA Filament in den ersten Schlauch der MMU und druecken Sie den Knopf, um es zu laden."
|
||||
|
||||
#MSG_PULL_OUT_FILAMENT c=20 r=4
|
||||
"Please pull out filament immediately"
|
||||
"Bitte ziehen Sie das Filament sofort heraus"
|
||||
@ -828,7 +776,7 @@
|
||||
|
||||
#
|
||||
"Press the knob"
|
||||
"Knopf druecken"
|
||||
"Knopf druecken zum"
|
||||
|
||||
#MSG_PRINT_PAUSED c=20 r=1
|
||||
"Print paused"
|
||||
@ -844,7 +792,19 @@
|
||||
|
||||
#
|
||||
"Print FAN"
|
||||
"Druckluefter"
|
||||
"Druckvent."
|
||||
|
||||
#
|
||||
"Please insert filament into the extruder, then press the knob to load it."
|
||||
"Bitte legen Sie das Filament in den Extruder ein und druecken Sie dann den Knopf, um es zu laden."
|
||||
|
||||
#
|
||||
"Please insert filament into the first tube of the MMU, then press the knob to load it."
|
||||
"Bitte stecken Sie das Filament in den ersten Schlauch der MMU und druecken Sie dann den Knopf, um es zu laden."
|
||||
|
||||
#
|
||||
"Please load filament first."
|
||||
"Bitte laden Sie zuerst das Filament."
|
||||
|
||||
#MSG_PRUSA3D
|
||||
"prusa3d.com"
|
||||
@ -868,7 +828,7 @@
|
||||
|
||||
#MSG_CALIBRATE_BED_RESET
|
||||
"Reset XYZ calibr."
|
||||
"XYZ Kalibr. zuruecksetzen."
|
||||
"Reset XYZ Kalibr."
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
"Reset"
|
||||
@ -886,25 +846,21 @@
|
||||
"Right side[um]"
|
||||
"Rechts [um]"
|
||||
|
||||
#MSG_SECOND_SERIAL_ON c=17 r=1
|
||||
"RPi port [on]"
|
||||
"RPi Port [an]"
|
||||
|
||||
#MSG_SECOND_SERIAL_OFF c=17 r=1
|
||||
"RPi port [off]"
|
||||
"RPi Port [aus]"
|
||||
#MSG_RPI_PORT
|
||||
"RPi port"
|
||||
"\x00"
|
||||
|
||||
#MSG_WIZARD_RERUN c=20 r=7
|
||||
"Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
"Der Assistent wird die aktuellen Kalibrierungsdaten loeschen und von vorne beginnen. Weiterfahren?"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1
|
||||
"SD card [normal]"
|
||||
"SD Karte [normal]"
|
||||
#MSG_SD_CARD
|
||||
"SD card"
|
||||
"SD Karte"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1
|
||||
"SD card [flshAir]"
|
||||
"SD Karte[flshAir]"
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY
|
||||
"FlashAir"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Right"
|
||||
@ -928,7 +884,7 @@
|
||||
|
||||
#MSG_SELFTEST
|
||||
"Selftest "
|
||||
"Selbsttest "
|
||||
"Selbsttest "
|
||||
|
||||
#MSG_SELFTEST_ERROR
|
||||
"Selftest error !"
|
||||
@ -936,7 +892,7 @@
|
||||
|
||||
#MSG_SELFTEST_FAILED c=20
|
||||
"Selftest failed "
|
||||
"Selbsttest misslung "
|
||||
"Selbsttest Error "
|
||||
|
||||
#MSG_FORCE_SELFTEST c=20 r=8
|
||||
"Selftest will be run to calibrate accurate sensorless rehoming."
|
||||
@ -946,10 +902,6 @@
|
||||
"Select nozzle preheat temperature which matches your material."
|
||||
"Bitte Vorheiztemperatur auswaehlen, die Ihrem Material entspricht."
|
||||
|
||||
#
|
||||
"Select PLA filament:"
|
||||
"PLA Filament auswaehlen:"
|
||||
|
||||
#MSG_SET_TEMPERATURE c=19 r=1
|
||||
"Set temperature:"
|
||||
"Temp. einstellen:"
|
||||
@ -970,49 +922,49 @@
|
||||
"Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
|
||||
"Einige Dateien wur- den nicht sortiert. Max. Dateien pro Verzeichnis = 100."
|
||||
|
||||
#MSG_SORT_NONE c=17 r=1
|
||||
"Sort [none]"
|
||||
"Sort. [Keine]"
|
||||
#MSG_SORT
|
||||
"Sort"
|
||||
"Sort."
|
||||
|
||||
#MSG_SORT_TIME c=17 r=1
|
||||
"Sort [time]"
|
||||
"Sort. [Zeit]"
|
||||
#MSG_NONE
|
||||
"None"
|
||||
"Ohne"
|
||||
|
||||
#MSG_SORT_TIME
|
||||
"Time"
|
||||
"Zeit"
|
||||
|
||||
#
|
||||
"Severe skew"
|
||||
"Schwerer Schraeglauf"
|
||||
"Severe skew:"
|
||||
"Schwer.Schr:"
|
||||
|
||||
#MSG_SORT_ALPHA c=17 r=1
|
||||
"Sort [alphabet]"
|
||||
"Sort. [Alphabet]"
|
||||
#MSG_SORT_ALPHA
|
||||
"Alphabet"
|
||||
"\x00"
|
||||
|
||||
#MSG_SORTING c=20 r=1
|
||||
"Sorting files"
|
||||
"Sortiere Dateien"
|
||||
|
||||
#MSG_SOUND_LOUD c=17 r=1
|
||||
"Sound [loud]"
|
||||
"Sound [laut]"
|
||||
#MSG_SOUND_LOUD
|
||||
"Loud"
|
||||
"Laut"
|
||||
|
||||
#
|
||||
"Slight skew"
|
||||
"Leichter Schraeglauf"
|
||||
"Slight skew:"
|
||||
"Leicht.Schr:"
|
||||
|
||||
#MSG_SOUND_MUTE c=17 r=1
|
||||
"Sound [mute]"
|
||||
"Sound [stumm]"
|
||||
#MSG_SOUND
|
||||
"Sound"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Some problem encountered, Z-leveling enforced ..."
|
||||
"Fehler aufgetreten, Z-Kalibrierung erforderlich..."
|
||||
|
||||
#MSG_SOUND_ONCE c=17 r=1
|
||||
"Sound [once]"
|
||||
"Sound [einmal]"
|
||||
|
||||
#MSG_SOUND_SILENT c=17 r=1
|
||||
"Sound [silent]"
|
||||
"Sound [leise]"
|
||||
#MSG_SOUND_ONCE
|
||||
"Once"
|
||||
"Einmal"
|
||||
|
||||
#MSG_SPEED
|
||||
"Speed"
|
||||
@ -1036,7 +988,7 @@
|
||||
|
||||
#MSG_STOPPED
|
||||
"STOPPED. "
|
||||
"GESTOPPT. "
|
||||
"GESTOPPT."
|
||||
|
||||
#MSG_SUPPORT
|
||||
"Support"
|
||||
@ -1046,17 +998,17 @@
|
||||
"Swapped"
|
||||
"Ausgetauscht"
|
||||
|
||||
#MSG_TEMP_CALIBRATION c=20 r=1
|
||||
"Temp. cal. "
|
||||
"Temp Kalib. "
|
||||
#
|
||||
"Select filament:"
|
||||
"Filament auswaehlen:"
|
||||
|
||||
#MSG_TEMP_CALIBRATION_ON c=20 r=1
|
||||
"Temp. cal. [on]"
|
||||
"Temp. Kal. [AN]"
|
||||
#MSG_TEMP_CALIBRATION c=12 r=1
|
||||
"Temp. cal."
|
||||
"Temp Kalib."
|
||||
|
||||
#MSG_TEMP_CALIBRATION_OFF c=20 r=1
|
||||
"Temp. cal. [off]"
|
||||
"Temp. Kal. [AUS]"
|
||||
#
|
||||
"Select temperature which matches your material."
|
||||
"Waehlen Sie die Temperatur, die zu Ihrem Material passt."
|
||||
|
||||
#MSG_CALIBRATION_PINDA_MENU c=17 r=1
|
||||
"Temp. calibration"
|
||||
@ -1104,11 +1056,11 @@
|
||||
|
||||
#
|
||||
"to load filament"
|
||||
"zum Filament laden"
|
||||
"Filament laden"
|
||||
|
||||
#
|
||||
"to unload filament"
|
||||
"zum Filament entladen"
|
||||
"Filament entladen"
|
||||
|
||||
#MSG_UNLOAD_FILAMENT c=17
|
||||
"Unload filament"
|
||||
@ -1230,15 +1182,166 @@
|
||||
"XYZ calibration failed. Right front calibration point not reachable."
|
||||
"XYZ-Kalibrierung fehlgeschlagen. Rechter vorderer Kalibrierpunkt ist nicht erreichbar."
|
||||
|
||||
|
||||
#
|
||||
"Y distance from min"
|
||||
"Y Entfernung vom Min"
|
||||
|
||||
#
|
||||
"The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Y-correct:"
|
||||
"Y-Korrektur:"
|
||||
|
||||
#MSG_OFF
|
||||
" [off]"
|
||||
"Off"
|
||||
"Aus"
|
||||
|
||||
#MSG_ON
|
||||
"On"
|
||||
"An"
|
||||
|
||||
#
|
||||
"Back"
|
||||
"Zurueck"
|
||||
|
||||
#
|
||||
"Checks"
|
||||
"Kontrolle"
|
||||
|
||||
#
|
||||
"False triggering"
|
||||
"Falschtriggerung"
|
||||
|
||||
#
|
||||
"FINDA:"
|
||||
"\x00"
|
||||
|
||||
#MSG_FIRMWARE
|
||||
"Firmware"
|
||||
"\x00"
|
||||
|
||||
#MSG_STRICT
|
||||
"Strict"
|
||||
"Strikt"
|
||||
|
||||
#MSG_WARN
|
||||
"Warn"
|
||||
"Warnen"
|
||||
|
||||
#
|
||||
"HW Setup"
|
||||
"HW Einstellungen"
|
||||
|
||||
#
|
||||
"IR:"
|
||||
"\x00"
|
||||
|
||||
#MSG_MAGNETS_COMP
|
||||
"Magnets comp."
|
||||
"Magnet Komp."
|
||||
|
||||
#MSG_MESH
|
||||
"Mesh"
|
||||
"Gitter"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"MeshBett Ausgleich"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"MK3S-Firmware auf MK3-Drucker erkannt"
|
||||
|
||||
#MSG_MMU_MODE
|
||||
"MMU Mode"
|
||||
"MMU Modus"
|
||||
|
||||
#
|
||||
"Mode change in progress ..."
|
||||
"Moduswechsel erfolgt..."
|
||||
|
||||
#MSG_MODEL
|
||||
"Model"
|
||||
"Modell"
|
||||
|
||||
#MSG_NOZZLE_DIAMETER
|
||||
"Nozzle d."
|
||||
"Duese D."
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Continue?"
|
||||
"G-Code ist fuer einen anderen Level geslict. Fortfahren?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
"G-Code ist fuer einen anderen Level geslict. Bitte slicen Sie das Modell erneut. Druck abgebrochen."
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-Code ist fuer einen anderen Drucker geslict. Fortfahren?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
"G-Code ist fuer einen anderen Drucker geslict. Bitte slicen Sie das Modell erneut. Druck abgebrochen."
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Continue?"
|
||||
"G-Code ist fuer eine neuere Firmware geslict. Fortfahren?"
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Please update the firmware. Print cancelled."
|
||||
"G-Code ist fuer eine neuere Firmware geslict. Bitte die Firmware updaten. Druck abgebrochen."
|
||||
|
||||
#
|
||||
"PINDA:"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Preheating to cut"
|
||||
"Heizen zum Schnitt"
|
||||
|
||||
#
|
||||
"Preheating to eject"
|
||||
"Heizen zum Auswurf"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Continue?"
|
||||
"Der Durchmesser der Druckerduese weicht vom G-Code ab. Fortfahren?"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
|
||||
"Der Durchmesser der Druckerduese weicht vom G-Code ab. Bitte ueberpruefen Sie den Wert in den Einstellungen. Druck abgebrochen."
|
||||
|
||||
#
|
||||
"Rename"
|
||||
"Umbenennen"
|
||||
|
||||
#
|
||||
"Select"
|
||||
"Auswahl"
|
||||
|
||||
#
|
||||
"Sensor info"
|
||||
"Sensor Info"
|
||||
|
||||
#
|
||||
"Sheet"
|
||||
"Blech"
|
||||
|
||||
#MSG_SOUND_BLIND
|
||||
"Assist"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Steel sheets"
|
||||
"Stahlbleche"
|
||||
|
||||
#
|
||||
"Z-correct:"
|
||||
"Z-Korrektur:"
|
||||
|
||||
#MSG_Z_PROBE_NR
|
||||
"Z-probe nr."
|
||||
"\x00"
|
||||
|
@ -1,3 +1,7 @@
|
||||
#
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
"[%.7s]Ajuste Z\x0aAjustado, continuar\x0ao empezar de nuevo?\x0a%cContinuar%cRepetir"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" de 4"
|
||||
@ -24,7 +28,7 @@
|
||||
|
||||
#MSG_BABYSTEPPING_Z c=15
|
||||
"Adjusting Z:"
|
||||
"Ajustar Z:"
|
||||
"Ajustar-Z:"
|
||||
|
||||
#MSG_SELFTEST_CHECK_ALLCORRECT c=20
|
||||
"All correct "
|
||||
@ -46,16 +50,8 @@
|
||||
"Are left and right Z~carriages all up?"
|
||||
"Carros Z izq./der. estan arriba maximo?"
|
||||
|
||||
#MSG_AUTO_DEPLETE_ON c=17 r=1
|
||||
"SpoolJoin [on]"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"SpoolJoin [N/A]"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_DEPLETE_OFF c=17 r=1
|
||||
"SpoolJoin [off]"
|
||||
#MSG_AUTO_DEPLETE c=17 r=1
|
||||
"SpoolJoin"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_HOME
|
||||
@ -68,11 +64,11 @@
|
||||
|
||||
#MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4
|
||||
"Autoloading filament available only when filament sensor is turned on..."
|
||||
"La carga automatica de filamento solo funciona si el sensor de filamento esta activado..."
|
||||
"La carga automatica solo funciona si el sensor de filamento esta activado..."
|
||||
|
||||
#MSG_AUTOLOADING_ENABLED c=20 r=4
|
||||
"Autoloading filament is active, just press the knob and insert filament..."
|
||||
"La carga automatica de filamento esta activada, pulse el dial e inserte el filamento..."
|
||||
"La carga automatica esta activada, pulse el dial e inserte el filamento..."
|
||||
|
||||
#MSG_SELFTEST_AXIS_LENGTH
|
||||
"Axis length"
|
||||
@ -104,7 +100,7 @@
|
||||
|
||||
#MSG_BED
|
||||
"Bed"
|
||||
"Base calefactable "
|
||||
"Base"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=15 r=1
|
||||
"Belt status"
|
||||
@ -170,17 +166,13 @@
|
||||
"Copy selected language?"
|
||||
"Copiar idioma seleccionado?"
|
||||
|
||||
#MSG_CRASHDETECT_ON
|
||||
"Crash det. [on]"
|
||||
"Det. choque [act]"
|
||||
#MSG_CRASHDETECT
|
||||
"Crash det."
|
||||
"Det. choque"
|
||||
|
||||
#MSG_CRASHDETECT_NA
|
||||
"Crash det. [N/A]"
|
||||
"Dec. choque [N/D]"
|
||||
|
||||
#MSG_CRASHDETECT_OFF
|
||||
"Crash det. [off]"
|
||||
"Det. choque [ina]"
|
||||
#
|
||||
"Choose a filament for the First Layer Calibration and select it in the on-screen menu."
|
||||
"Escoge un filamento para la Calibracion de la Primera Capa y seleccionalo en el menu en pantalla."
|
||||
|
||||
#MSG_CRASH_DETECTED c=20 r=1
|
||||
"Crash detected."
|
||||
@ -216,16 +208,12 @@
|
||||
|
||||
#MSG_EXTRUDER_CORRECTION c=10
|
||||
"E-correct:"
|
||||
"E-correcion:"
|
||||
"Corregir-E:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
"Eject filament"
|
||||
"Expulsar filamento"
|
||||
|
||||
#
|
||||
"Eject"
|
||||
"Expulsar"
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
"Expulsando filamento"
|
||||
@ -256,7 +244,7 @@
|
||||
|
||||
#MSG_SELFTEST_EXTRUDER_FAN_SPEED c=18
|
||||
"Extruder fan:"
|
||||
"Ventilador del extrusor:"
|
||||
"Vent.extrusor:"
|
||||
|
||||
#MSG_INFO_EXTRUDER c=15 r=1
|
||||
"Extruder info"
|
||||
@ -270,17 +258,9 @@
|
||||
"Fail stats MMU"
|
||||
"Estadistica de fallos MMU"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_ON c=17 r=1
|
||||
"F. autoload [on]"
|
||||
"Autocarg.Fil[act]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_NA c=17 r=1
|
||||
"F. autoload [N/A]"
|
||||
"Autocarg.Fil[N/D]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_OFF c=17 r=1
|
||||
"F. autoload [off]"
|
||||
"Autocarg.Fil[ina]"
|
||||
#MSG_FSENSOR_AUTOLOAD
|
||||
"F. autoload"
|
||||
"Autocarg.fil."
|
||||
|
||||
#
|
||||
"Fail stats"
|
||||
@ -294,25 +274,13 @@
|
||||
"Fan test"
|
||||
"Test ventiladores"
|
||||
|
||||
#MSG_FANS_CHECK_ON c=17 r=1
|
||||
"Fans check [on]"
|
||||
"Comprob.vent[act]"
|
||||
#MSG_FANS_CHECK
|
||||
"Fans check"
|
||||
"Comprob.vent"
|
||||
|
||||
#MSG_FANS_CHECK_OFF c=17 r=1
|
||||
"Fans check [off]"
|
||||
"Comprob.vent[ina]"
|
||||
|
||||
#MSG_FSENSOR_ON
|
||||
"Fil. sensor [on]"
|
||||
"Sensor Fil. [act]"
|
||||
|
||||
#MSG_FSENSOR_NA
|
||||
"Fil. sensor [N/A]"
|
||||
"Sensor Fil. [N/D]"
|
||||
|
||||
#MSG_FSENSOR_OFF
|
||||
"Fil. sensor [off]"
|
||||
"Sensor Fil. [ina]"
|
||||
#MSG_FSENSOR
|
||||
"Fil. sensor"
|
||||
"Sensor Fil."
|
||||
|
||||
#
|
||||
"Filam. runouts"
|
||||
@ -462,18 +430,10 @@
|
||||
"I will run z calibration now."
|
||||
"Voy a hacer Calibracion Z ahora."
|
||||
|
||||
#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."
|
||||
"Voy a comenzar a imprimir la linea y tu bajaras el nozzle gradualmente al rotar el dial, hasta que llegues a la altura optima. Mira las imagenes del capitulo Calibracion en el manual."
|
||||
|
||||
#MSG_WATCH
|
||||
"Info screen"
|
||||
"Monitorizar"
|
||||
|
||||
#
|
||||
"Is filament 1 loaded?"
|
||||
"?Esta cargado el filamento 1?"
|
||||
|
||||
#MSG_INSERT_FILAMENT c=20
|
||||
"Insert filament"
|
||||
"Introducir filamento"
|
||||
@ -482,14 +442,6 @@
|
||||
"Is filament loaded?"
|
||||
"Esta el filamento cargado?"
|
||||
|
||||
#MSG_WIZARD_PLA_FILAMENT c=20 r=2
|
||||
"Is it PLA filament?"
|
||||
"Es el filamento PLA?"
|
||||
|
||||
#MSG_PLA_FILAMENT_LOADED c=20 r=2
|
||||
"Is PLA filament loaded?"
|
||||
"Esta el filamento PLA cargado?"
|
||||
|
||||
#MSG_STEEL_SHEET_CHECK c=20 r=2
|
||||
"Is steel sheet on heatbed?"
|
||||
"?Esta colocada la lamina de acero sobre la base?"
|
||||
@ -498,6 +450,10 @@
|
||||
"Last print failures"
|
||||
"Ultimas impresiones fallidas"
|
||||
|
||||
#
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
"Si tienes planchas de acero adicionales, calibra sus ajustes en Ajustes - Ajustes HW - Planchas acero."
|
||||
|
||||
#
|
||||
"Last print"
|
||||
"Ultima impresion"
|
||||
@ -568,7 +524,7 @@
|
||||
|
||||
#
|
||||
"Measured skew"
|
||||
"Desviacion medida:"
|
||||
"Desviacion med:"
|
||||
|
||||
#
|
||||
"MMU fails"
|
||||
@ -586,13 +542,17 @@
|
||||
"MMU OK. Resuming..."
|
||||
"MMU OK. Resumiendo..."
|
||||
|
||||
#MSG_STEALTH_MODE_OFF
|
||||
"Mode [Normal]"
|
||||
"Modo [Normal]"
|
||||
#MSG_MODE
|
||||
"Mode"
|
||||
"Modo"
|
||||
|
||||
#MSG_SILENT_MODE_ON
|
||||
"Mode [silent]"
|
||||
"Modo [silencio]"
|
||||
#MSG_NORMAL
|
||||
"Normal"
|
||||
"\x00"
|
||||
|
||||
#MSG_SILENT
|
||||
"Silent"
|
||||
"Silencio"
|
||||
|
||||
#
|
||||
"MMU needs user attention."
|
||||
@ -602,17 +562,17 @@
|
||||
"MMU power fails"
|
||||
"Fallo de energia en MMU"
|
||||
|
||||
#MSG_STEALTH_MODE_ON
|
||||
"Mode [Stealth]"
|
||||
"Modo [Silencio]"
|
||||
#MSG_STEALTH
|
||||
"Stealth"
|
||||
"Silencio"
|
||||
|
||||
#MSG_AUTO_MODE_ON
|
||||
"Mode [auto power]"
|
||||
"Modo[fuerza auto]"
|
||||
#MSG_AUTO_POWER
|
||||
"Auto power"
|
||||
"Fuerza auto"
|
||||
|
||||
#MSG_SILENT_MODE_OFF
|
||||
"Mode [high power]"
|
||||
"Modo [rend.pleno]"
|
||||
#MSG_HIGH_POWER
|
||||
"High power"
|
||||
"Rend.pleno"
|
||||
|
||||
#
|
||||
"MMU2 connected"
|
||||
@ -646,9 +606,9 @@
|
||||
"No SD card"
|
||||
"No hay tarjeta SD"
|
||||
|
||||
#
|
||||
#MSG_NA
|
||||
"N/A"
|
||||
"N/A"
|
||||
"No disponible"
|
||||
|
||||
#MSG_NO
|
||||
"No"
|
||||
@ -672,7 +632,7 @@
|
||||
|
||||
#MSG_WIZARD_WILL_PREHEAT c=20 r=4
|
||||
"Now I will preheat nozzle for PLA."
|
||||
"Voy a precalentar la boquilla para PLA ahora."
|
||||
"Ahora precalentare la boquilla para PLA."
|
||||
|
||||
#MSG_NOZZLE
|
||||
"Nozzle"
|
||||
@ -688,7 +648,7 @@
|
||||
|
||||
#
|
||||
"Nozzle FAN"
|
||||
"Ventilador de capa"
|
||||
"Vent. capa"
|
||||
|
||||
#MSG_PAUSE_PRINT
|
||||
"Pause print"
|
||||
@ -730,14 +690,6 @@
|
||||
"Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
"Lee el manual y resuelve el problema. Despues, reinicia la impresora y continua con el Wizard"
|
||||
|
||||
#MSG_WIZARD_LOAD_FILAMENT c=20 r=8
|
||||
"Please insert PLA filament to the extruder, then press knob to load it."
|
||||
"Inserta, por favor, filamento PLA en el extrusor. Despues haz clic para cargarlo."
|
||||
|
||||
#MSG_PLEASE_LOAD_PLA c=20 r=4
|
||||
"Please load PLA filament first."
|
||||
"Carga el filamento PLA primero por favor."
|
||||
|
||||
#MSG_CHECK_IDLER c=20 r=4
|
||||
"Please open idler and remove filament manually."
|
||||
"Por favor abate el rodillo de empuje (idler) y retira el filamento manualmente."
|
||||
@ -750,10 +702,6 @@
|
||||
"Please press the knob to unload filament"
|
||||
"Por favor, pulsa el dial para descargar el filamento"
|
||||
|
||||
#
|
||||
"Please insert PLA filament to the first tube of MMU, then press the knob to load it."
|
||||
"Por favor introduce el filamento al primer tubo MMU, despues presiona el dial para imprimirlo."
|
||||
|
||||
#MSG_PULL_OUT_FILAMENT c=20 r=4
|
||||
"Please pull out filament immediately"
|
||||
"Por favor retire el filamento de inmediato"
|
||||
@ -820,7 +768,7 @@
|
||||
|
||||
#MSG_SELFTEST_PRINT_FAN_SPEED c=18
|
||||
"Print fan:"
|
||||
"Ventilador del fusor:"
|
||||
"Vent.fusor:"
|
||||
|
||||
#MSG_CARD_MENU
|
||||
"Print from SD"
|
||||
@ -844,7 +792,19 @@
|
||||
|
||||
#
|
||||
"Print FAN"
|
||||
"Ventilador del extrusor"
|
||||
"Vent. extr"
|
||||
|
||||
#
|
||||
"Please insert filament into the extruder, then press the knob to load it."
|
||||
"Por favor, coloca el filamento en el extrusor, luego presiona el dial para cargarlo."
|
||||
|
||||
#
|
||||
"Please insert filament into the first tube of the MMU, then press the knob to load it."
|
||||
"Por favor, coloca el filamento en el primer tubo de la MMU, luego pulsa el dial para cargarlo."
|
||||
|
||||
#
|
||||
"Please load filament first."
|
||||
"Por favor, cargar primero el filamento. "
|
||||
|
||||
#MSG_PRUSA3D
|
||||
"prusa3d.com"
|
||||
@ -880,31 +840,27 @@
|
||||
|
||||
#MSG_RESUMING_PRINT c=20 r=1
|
||||
"Resuming print"
|
||||
"Resumiendo impresion"
|
||||
"Continuando impresion"
|
||||
|
||||
#MSG_BED_CORRECTION_RIGHT c=14 r=1
|
||||
"Right side[um]"
|
||||
"Derecha [um]"
|
||||
|
||||
#MSG_SECOND_SERIAL_ON c=17 r=1
|
||||
"RPi port [on]"
|
||||
"Puerto RPi [act]"
|
||||
|
||||
#MSG_SECOND_SERIAL_OFF c=17 r=1
|
||||
"RPi port [off]"
|
||||
"Puerto RPi [ina]"
|
||||
#MSG_RPI_PORT
|
||||
"RPi port"
|
||||
"Puerto RPi"
|
||||
|
||||
#MSG_WIZARD_RERUN c=20 r=7
|
||||
"Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
"Ejecutar el Wizard borrara los valores de calibracion actuales y comenzara de nuevo. Continuar?"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1
|
||||
"SD card [normal]"
|
||||
"Tarj. SD [normal]"
|
||||
#MSG_SD_CARD
|
||||
"SD card"
|
||||
"Tarj. SD"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1
|
||||
"SD card [flshAir]"
|
||||
"Tarj. SD[FlshAir]"
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY
|
||||
"FlashAir"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Right"
|
||||
@ -946,10 +902,6 @@
|
||||
"Select nozzle preheat temperature which matches your material."
|
||||
"Selecciona la temperatura para precalentar la boquilla que se ajuste a tu material. "
|
||||
|
||||
#
|
||||
"Select PLA filament:"
|
||||
"Seleccionar filamento PLA:"
|
||||
|
||||
#MSG_SET_TEMPERATURE c=19 r=1
|
||||
"Set temperature:"
|
||||
"Establecer temp.:"
|
||||
@ -970,49 +922,49 @@
|
||||
"Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
|
||||
"Algunos archivos no se ordenaran. Maximo 100 archivos por carpeta para ordenar. "
|
||||
|
||||
#MSG_SORT_NONE c=17 r=1
|
||||
"Sort [none]"
|
||||
"Ordenar [nada]"
|
||||
#MSG_SORT
|
||||
"Sort"
|
||||
"Ordenar"
|
||||
|
||||
#MSG_SORT_TIME c=17 r=1
|
||||
"Sort [time]"
|
||||
"Ordenar [Fecha]"
|
||||
#MSG_NONE
|
||||
"None"
|
||||
"Ninguno"
|
||||
|
||||
#MSG_SORT_TIME
|
||||
"Time"
|
||||
"Fecha"
|
||||
|
||||
#
|
||||
"Severe skew"
|
||||
"Inclinacion severa"
|
||||
"Severe skew:"
|
||||
"Incl.severa:"
|
||||
|
||||
#MSG_SORT_ALPHA c=17 r=1
|
||||
"Sort [alphabet]"
|
||||
"Ordenar [alfabet]"
|
||||
#MSG_SORT_ALPHA
|
||||
"Alphabet"
|
||||
"Alfabet"
|
||||
|
||||
#MSG_SORTING c=20 r=1
|
||||
"Sorting files"
|
||||
"Ordenando archivos"
|
||||
|
||||
#MSG_SOUND_LOUD c=17 r=1
|
||||
"Sound [loud]"
|
||||
"Sonido [alto]"
|
||||
#MSG_SOUND_LOUD
|
||||
"Loud"
|
||||
"Alto"
|
||||
|
||||
#
|
||||
"Slight skew"
|
||||
"Ligeramente inclinado"
|
||||
"Slight skew:"
|
||||
"Liger.incl.:"
|
||||
|
||||
#MSG_SOUND_MUTE c=17 r=1
|
||||
"Sound [mute]"
|
||||
"Sonido[silenciad]"
|
||||
#MSG_SOUND
|
||||
"Sound"
|
||||
"Sonido"
|
||||
|
||||
#
|
||||
"Some problem encountered, Z-leveling enforced ..."
|
||||
"Problema encontrado, nivelacion Z forzosa ..."
|
||||
|
||||
#MSG_SOUND_ONCE c=17 r=1
|
||||
"Sound [once]"
|
||||
"Sonido [una vez]"
|
||||
|
||||
#MSG_SOUND_SILENT c=17 r=1
|
||||
"Sound [silent]"
|
||||
"Sonido[silencios]"
|
||||
#MSG_SOUND_ONCE
|
||||
"Once"
|
||||
"Una vez"
|
||||
|
||||
#MSG_SPEED
|
||||
"Speed"
|
||||
@ -1046,17 +998,17 @@
|
||||
"Swapped"
|
||||
"Intercambiado"
|
||||
|
||||
#MSG_TEMP_CALIBRATION c=20 r=1
|
||||
"Temp. cal. "
|
||||
"Cal. temp. "
|
||||
#
|
||||
"Select filament:"
|
||||
"Selecciona filamento:"
|
||||
|
||||
#MSG_TEMP_CALIBRATION_ON c=20 r=1
|
||||
"Temp. cal. [on]"
|
||||
"Cal. temp. [ON]"
|
||||
#MSG_TEMP_CALIBRATION c=12 r=1
|
||||
"Temp. cal."
|
||||
"Cal. temp."
|
||||
|
||||
#MSG_TEMP_CALIBRATION_OFF c=20 r=1
|
||||
"Temp. cal. [off]"
|
||||
"Cal. temp. [OFF]"
|
||||
#
|
||||
"Select temperature which matches your material."
|
||||
"Selecciona la temperatura adecuada a tu material."
|
||||
|
||||
#MSG_CALIBRATION_PINDA_MENU c=17 r=1
|
||||
"Temp. calibration"
|
||||
@ -1084,11 +1036,11 @@
|
||||
|
||||
#
|
||||
"Total filament"
|
||||
"Filamento total:"
|
||||
"Filamento total"
|
||||
|
||||
#
|
||||
"Total print time"
|
||||
"Tiempo total :"
|
||||
"Tiempo total"
|
||||
|
||||
#MSG_TUNE
|
||||
"Tune"
|
||||
@ -1200,7 +1152,7 @@
|
||||
|
||||
#
|
||||
"X-correct:"
|
||||
"X-correcion:"
|
||||
"Corregir-X:"
|
||||
|
||||
#MSG_BED_SKEW_OFFSET_DETECTION_PERFECT c=20 r=8
|
||||
"XYZ calibration ok. X/Y axes are perpendicular. Congratulations!"
|
||||
@ -1234,10 +1186,162 @@
|
||||
"Y distance from min"
|
||||
"Distancia en Y desde el min"
|
||||
|
||||
#
|
||||
"The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Y-correct:"
|
||||
"Y-correcion:"
|
||||
"Corregir-Y:"
|
||||
|
||||
#MSG_OFF
|
||||
" [off]"
|
||||
"Off"
|
||||
"Ina"
|
||||
|
||||
#MSG_ON
|
||||
"On"
|
||||
"Act"
|
||||
|
||||
#
|
||||
"Back"
|
||||
"atras"
|
||||
|
||||
#
|
||||
"Checks"
|
||||
"Comprobaciones"
|
||||
|
||||
#
|
||||
"False triggering"
|
||||
"Falsa activacion"
|
||||
|
||||
#
|
||||
"FINDA:"
|
||||
"FINDA:"
|
||||
|
||||
#MSG_FIRMWARE
|
||||
"Firmware"
|
||||
"\x00"
|
||||
|
||||
#MSG_STRICT
|
||||
"Strict"
|
||||
"Estrict"
|
||||
|
||||
#MSG_WARN
|
||||
"Warn"
|
||||
"Aviso"
|
||||
|
||||
#
|
||||
"HW Setup"
|
||||
"Configuracion HW"
|
||||
|
||||
#
|
||||
"IR:"
|
||||
"\x00"
|
||||
|
||||
#MSG_MAGNETS_COMP
|
||||
"Magnets comp."
|
||||
"Comp. imanes"
|
||||
|
||||
#MSG_MESH
|
||||
"Mesh"
|
||||
"Malla"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Nivelacion Malla Base"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"Firmware MK3S detectado en impresora MK3"
|
||||
|
||||
#MSG_MMU_MODE
|
||||
"MMU Mode"
|
||||
"Modo MMU"
|
||||
|
||||
#
|
||||
"Mode change in progress ..."
|
||||
"Cambio de modo progresando ..."
|
||||
|
||||
#MSG_MODEL
|
||||
"Model"
|
||||
"Modelo"
|
||||
|
||||
#MSG_NOZZLE_DIAMETER
|
||||
"Nozzle d."
|
||||
"Diam. nozzl"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Continue?"
|
||||
"Codigo G laminado para un nivel diferente. ?Continuar?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
"Codigo G laminado para un nivel diferente. Por favor relamina el modelo de nuevo. Impresion cancelada."
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"Codigo G laminado para un tipo de impresora diferente. ?Continuar?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
"Codigo G laminado para una impresora diferente. Por favor relamina el modelo de nuevo. Impresion cancelada."
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Continue?"
|
||||
"Codigo G laminado para nuevo firmware. ?Continuar?"
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Please update the firmware. Print cancelled."
|
||||
"Codigo G laminado para nuevo firmware. Por favor actualiza el firmware. Impresion cancelada."
|
||||
|
||||
#
|
||||
"PINDA:"
|
||||
"PINDA:"
|
||||
|
||||
#
|
||||
"Preheating to cut"
|
||||
"Precalentando para laminar"
|
||||
|
||||
#
|
||||
"Preheating to eject"
|
||||
"Precalentar para expulsar"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Continue?"
|
||||
"Diametro nozzle impresora difiere de cod.G. ?Continuar?"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
|
||||
"Diametro nozzle Impresora difiere de cod.G. Comprueba los valores en ajustes. Impresion cancelada."
|
||||
|
||||
#
|
||||
"Rename"
|
||||
"Renombrar"
|
||||
|
||||
#
|
||||
"Select"
|
||||
"Seleccionar"
|
||||
|
||||
#
|
||||
"Sensor info"
|
||||
"Info sensor"
|
||||
|
||||
#
|
||||
"Sheet"
|
||||
"Lamina"
|
||||
|
||||
#MSG_SOUND_BLIND
|
||||
"Assist"
|
||||
"Asistido"
|
||||
|
||||
#
|
||||
"Steel sheets"
|
||||
"Lamina de acero"
|
||||
|
||||
#
|
||||
"Z-correct:"
|
||||
"Corregir-Z:"
|
||||
|
||||
#MSG_Z_PROBE_NR
|
||||
"Z-probe nr."
|
||||
"Z-sensor nr."
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -1,10 +1,14 @@
|
||||
#
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
"[%.7s]Set valori\x0aComp. Z, continuare\x0ao iniziare da zero?\x0a%cContinua%cReset"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" su 4"
|
||||
|
||||
#MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 c=14
|
||||
" of 9"
|
||||
"su 9"
|
||||
" su 9"
|
||||
|
||||
#MSG_MEASURED_OFFSET
|
||||
"[0;0] point offset"
|
||||
@ -15,7 +19,7 @@
|
||||
"Rilev. impatto\x0aattivabile solo\x0ain Modalita normale"
|
||||
|
||||
#MSG_CRASH_DET_STEALTH_FORCE_OFF c=20 r=4
|
||||
"WARNING:\x0aCrash detection disabled in Stealth mode"
|
||||
"WARNING:\x0aCrash detection\x0adisabled in\x0aStealth mode"
|
||||
"ATTENZIONE:\x0aRilev. impatto\x0adisattivato in\x0aModalita silenziosa"
|
||||
|
||||
#
|
||||
@ -46,16 +50,8 @@
|
||||
"Are left and right Z~carriages all up?"
|
||||
"I carrelli Z sin/des sono altezza max?"
|
||||
|
||||
#MSG_AUTO_DEPLETE_ON c=17 r=1
|
||||
"SpoolJoin [on]"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"SpoolJoin [N/A]"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_DEPLETE_OFF c=17 r=1
|
||||
"SpoolJoin [off]"
|
||||
#MSG_AUTO_DEPLETE c=17 r=1
|
||||
"SpoolJoin"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_HOME
|
||||
@ -72,7 +68,7 @@
|
||||
|
||||
#MSG_AUTOLOADING_ENABLED c=20 r=4
|
||||
"Autoloading filament is active, just press the knob and insert filament..."
|
||||
"Il caricamento automatico e attivo, premete la manopola e inserite il filamento..."
|
||||
"Caricamento automatico attivo, premi la manopola e inserisci il filamento."
|
||||
|
||||
#MSG_SELFTEST_AXIS_LENGTH
|
||||
"Axis length"
|
||||
@ -108,7 +104,7 @@
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=15 r=1
|
||||
"Belt status"
|
||||
"Stato delle cinghie"
|
||||
"Stato cinghie"
|
||||
|
||||
#MSG_RECOVER_PRINT c=20 r=2
|
||||
"Blackout occurred. Recover print?"
|
||||
@ -170,17 +166,13 @@
|
||||
"Copy selected language?"
|
||||
"Copiare la lingua selezionata?"
|
||||
|
||||
#MSG_CRASHDETECT_ON
|
||||
"Crash det. [on]"
|
||||
"Rilevam.imp. [on]"
|
||||
#MSG_CRASHDETECT
|
||||
"Crash det."
|
||||
"Rileva.crash"
|
||||
|
||||
#MSG_CRASHDETECT_NA
|
||||
"Crash det. [N/A]"
|
||||
"Rilevam.imp.[N/A]"
|
||||
|
||||
#MSG_CRASHDETECT_OFF
|
||||
"Crash det. [off]"
|
||||
"Rilevam.imp.[off]"
|
||||
#
|
||||
"Choose a filament for the First Layer Calibration and select it in the on-screen menu."
|
||||
"Scegli un filamento per la calibrazione del primo strato e selezionalo nel menu sullo schermo."
|
||||
|
||||
#MSG_CRASH_DETECTED c=20 r=1
|
||||
"Crash detected."
|
||||
@ -222,10 +214,6 @@
|
||||
"Eject filament"
|
||||
"Espelli filamento "
|
||||
|
||||
#
|
||||
"Eject"
|
||||
"Espellere"
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
"Espellendo filamento "
|
||||
@ -256,7 +244,7 @@
|
||||
|
||||
#MSG_SELFTEST_EXTRUDER_FAN_SPEED c=18
|
||||
"Extruder fan:"
|
||||
"Ventola estrusore:"
|
||||
"Ventola estr:"
|
||||
|
||||
#MSG_INFO_EXTRUDER c=15 r=1
|
||||
"Extruder info"
|
||||
@ -268,52 +256,31 @@
|
||||
|
||||
#
|
||||
"Fail stats MMU"
|
||||
"Statistiche fallimenti MMU"
|
||||
"Stat.fall. MMU"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_ON c=17 r=1
|
||||
"F. autoload [on]"
|
||||
"Autocar.filam[on]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_NA c=17 r=1
|
||||
"F. autoload [N/A]"
|
||||
"Autocar.fil.[N/A]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_OFF c=17 r=1
|
||||
"F. autoload [off]"
|
||||
"Autocar.fil.[off]"
|
||||
#MSG_FSENSOR_AUTOLOAD
|
||||
"F. autoload"
|
||||
"Autocar.fil."
|
||||
|
||||
#
|
||||
"Fail stats"
|
||||
"Statistiche fallimenti"
|
||||
"Stat. fallimenti"
|
||||
|
||||
#MSG_FAN_SPEED c=14
|
||||
"Fan speed"
|
||||
"Velocita ventola"
|
||||
"Velocita vent."
|
||||
|
||||
#MSG_SELFTEST_FAN c=20
|
||||
"Fan test"
|
||||
"Test ventola"
|
||||
|
||||
#MSG_FANS_CHECK_ON c=17 r=1
|
||||
"Fans check [on]"
|
||||
"Controllo ventole [on]"
|
||||
|
||||
#MSG_FANS_CHECK_OFF c=17 r=1
|
||||
"Fans check [off]"
|
||||
"Control.vent[off]"
|
||||
|
||||
#MSG_FSENSOR_ON
|
||||
"Fil. sensor [on]"
|
||||
"Sensor filam.[On]"
|
||||
|
||||
#MSG_FSENSOR_NA
|
||||
"Fil. sensor [N/A]"
|
||||
"Sensor filam[N/A]"
|
||||
|
||||
#MSG_FSENSOR_OFF
|
||||
"Fil. sensor [off]"
|
||||
"Sensor filam[off]"
|
||||
#MSG_FANS_CHECK
|
||||
"Fans check"
|
||||
"Control.vent"
|
||||
|
||||
#MSG_FSENSOR
|
||||
"Fil. sensor"
|
||||
"Sensore fil."
|
||||
#
|
||||
"Filam. runouts"
|
||||
"Filam. esauriti"
|
||||
@ -348,7 +315,7 @@
|
||||
|
||||
#MSG_V2_CALIBRATION c=17 r=1
|
||||
"First layer cal."
|
||||
"Calibrazione primo layer."
|
||||
"Cal. primo strato"
|
||||
|
||||
#MSG_WIZARD_SELFTEST c=20 r=8
|
||||
"First, I will run the selftest to check most common assembly problems."
|
||||
@ -462,18 +429,10 @@
|
||||
"I will run z calibration now."
|
||||
"Adesso avviero la Calibrazione Z."
|
||||
|
||||
#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."
|
||||
"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_WATCH
|
||||
"Info screen"
|
||||
"Schermata info"
|
||||
|
||||
#
|
||||
"Is filament 1 loaded?"
|
||||
"Il filamento 1 e caricato?"
|
||||
|
||||
#MSG_INSERT_FILAMENT c=20
|
||||
"Insert filament"
|
||||
"Inserire filamento"
|
||||
@ -482,14 +441,6 @@
|
||||
"Is filament loaded?"
|
||||
"Il filamento e stato caricato?"
|
||||
|
||||
#MSG_WIZARD_PLA_FILAMENT c=20 r=2
|
||||
"Is it PLA filament?"
|
||||
"E' un filamento di PLA?"
|
||||
|
||||
#MSG_PLA_FILAMENT_LOADED c=20 r=2
|
||||
"Is PLA filament loaded?"
|
||||
"E' stato caricato il filamento di PLA?"
|
||||
|
||||
#MSG_STEEL_SHEET_CHECK c=20 r=2
|
||||
"Is steel sheet on heatbed?"
|
||||
"La piastra d'acciaio e sul piano riscaldato?"
|
||||
@ -498,6 +449,10 @@
|
||||
"Last print failures"
|
||||
"Fallimenti ultima stampa"
|
||||
|
||||
#
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
"Se hai piastre d'acciaio aggiuntive, calibra i preset in Impostazioni - Setup HW - Piastre in Acciaio."
|
||||
|
||||
#
|
||||
"Last print"
|
||||
"Ultima stampa"
|
||||
@ -512,11 +467,11 @@
|
||||
|
||||
#MSG_BED_CORRECTION_LEFT c=14 r=1
|
||||
"Left side [um]"
|
||||
"Lato sinistro [um]"
|
||||
"Sinistra [um]"
|
||||
|
||||
#
|
||||
"Lin. correction"
|
||||
"Correzione lin."
|
||||
"Correzione lineare"
|
||||
|
||||
#MSG_BABYSTEP_Z
|
||||
"Live adjust Z"
|
||||
@ -556,7 +511,7 @@
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
"Mesh Bed Leveling"
|
||||
"Mesh livel. letto"
|
||||
"Livel. piatto"
|
||||
|
||||
#MSG_MMU_OK_RESUMING_POSITION c=20 r=4
|
||||
"MMU OK. Resuming position..."
|
||||
@ -568,7 +523,7 @@
|
||||
|
||||
#
|
||||
"Measured skew"
|
||||
"Disassamento misurato"
|
||||
"Deviazione mis"
|
||||
|
||||
#
|
||||
"MMU fails"
|
||||
@ -586,13 +541,17 @@
|
||||
"MMU OK. Resuming..."
|
||||
"MMU OK. Riprendendo... "
|
||||
|
||||
#MSG_STEALTH_MODE_OFF
|
||||
"Mode [Normal]"
|
||||
"Modo [normale]"
|
||||
#MSG_MODE
|
||||
"Mode"
|
||||
"Mod."
|
||||
|
||||
#MSG_SILENT_MODE_ON
|
||||
"Mode [silent]"
|
||||
"Modo [silenzioso]"
|
||||
#MSG_NORMAL
|
||||
"Normal"
|
||||
"Normale"
|
||||
|
||||
#MSG_SILENT
|
||||
"Silent"
|
||||
"Silenzioso"
|
||||
|
||||
#
|
||||
"MMU needs user attention."
|
||||
@ -600,19 +559,19 @@
|
||||
|
||||
#
|
||||
"MMU power fails"
|
||||
"Mancanza corrente MMU"
|
||||
"Manc. corr. MMU"
|
||||
|
||||
#MSG_STEALTH_MODE_ON
|
||||
"Mode [Stealth]"
|
||||
"Modo [Silenziosa]"
|
||||
#MSG_STEALTH
|
||||
"Stealth"
|
||||
"Silenziosa"
|
||||
|
||||
#MSG_AUTO_MODE_ON
|
||||
"Mode [auto power]"
|
||||
"Modo [auto]"
|
||||
#MSG_AUTO_POWER
|
||||
"Auto power"
|
||||
"Auto"
|
||||
|
||||
#MSG_SILENT_MODE_OFF
|
||||
"Mode [high power]"
|
||||
"Mode [forte]"
|
||||
#MSG_HIGH_POWER
|
||||
"High power"
|
||||
"Forte"
|
||||
|
||||
#
|
||||
"MMU2 connected"
|
||||
@ -628,15 +587,15 @@
|
||||
|
||||
#MSG_MOVE_X
|
||||
"Move X"
|
||||
"Muovi X"
|
||||
"Sposta X"
|
||||
|
||||
#MSG_MOVE_Y
|
||||
"Move Y"
|
||||
"Muovi Y"
|
||||
"Sposta Y"
|
||||
|
||||
#MSG_MOVE_Z
|
||||
"Move Z"
|
||||
"Muovi Z"
|
||||
"Sposta Z"
|
||||
|
||||
#MSG_NO_MOVE
|
||||
"No move."
|
||||
@ -646,7 +605,7 @@
|
||||
"No SD card"
|
||||
"Nessuna SD"
|
||||
|
||||
#
|
||||
#MSG_NA
|
||||
"N/A"
|
||||
"\x00"
|
||||
|
||||
@ -680,7 +639,7 @@
|
||||
|
||||
#MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
|
||||
"Old settings found. Default PID, Esteps etc. will be set."
|
||||
"Sono state trovate impostazioni vecchie. I valori di default di PID, Esteps etc. saranno impostati"
|
||||
"Sono state trovate impostazioni vecchie. Verranno impostati i valori predefiniti di PID, Esteps etc."
|
||||
|
||||
#
|
||||
"Now remove the test print from steel sheet."
|
||||
@ -730,14 +689,6 @@
|
||||
"Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
"Per favore consulta il nostro manuale per risolvere il problema. Poi riprendi il Wizard dopo aver riavviato la stampante."
|
||||
|
||||
#MSG_WIZARD_LOAD_FILAMENT c=20 r=8
|
||||
"Please insert PLA filament to the extruder, then press knob to load it."
|
||||
"Per favore inserisci il filamento di PLA nell'estrusore, poi premi la manopola per caricare."
|
||||
|
||||
#MSG_PLEASE_LOAD_PLA c=20 r=4
|
||||
"Please load PLA filament first."
|
||||
"Per favore prima carica il filamento di PLA."
|
||||
|
||||
#MSG_CHECK_IDLER c=20 r=4
|
||||
"Please open idler and remove filament manually."
|
||||
"Aprire la guida filam. e rimuovere il filam. a mano"
|
||||
@ -750,10 +701,6 @@
|
||||
"Please press the knob to unload filament"
|
||||
"Premete la manopola per scaricare il filamento "
|
||||
|
||||
#
|
||||
"Please insert PLA filament to the first tube of MMU, then press the knob to load it."
|
||||
"Per favore inserite del filamento PLA nel primo tubo del MMU, poi premete la manopola per caricarlo."
|
||||
|
||||
#MSG_PULL_OUT_FILAMENT c=20 r=4
|
||||
"Please pull out filament immediately"
|
||||
"Estrarre il filamento immediatamente"
|
||||
@ -820,7 +767,7 @@
|
||||
|
||||
#MSG_SELFTEST_PRINT_FAN_SPEED c=18
|
||||
"Print fan:"
|
||||
"Ventola di stampa:"
|
||||
"Vent.stam:"
|
||||
|
||||
#MSG_CARD_MENU
|
||||
"Print from SD"
|
||||
@ -846,6 +793,18 @@
|
||||
"Print FAN"
|
||||
"Ventola di stampa"
|
||||
|
||||
#
|
||||
"Please insert filament into the extruder, then press the knob to load it."
|
||||
"Inserisci il filamento nell'estrusore, poi premi la manopola per caricarlo."
|
||||
|
||||
#
|
||||
"Please insert filament into the first tube of the MMU, then press the knob to load it."
|
||||
"Per favore inserisci il filamento nel primo tubo del MMU, poi premi la manopola per caricarlo."
|
||||
|
||||
#
|
||||
"Please load filament first."
|
||||
"Per favore prima carica il filamento."
|
||||
|
||||
#MSG_PRUSA3D
|
||||
"prusa3d.com"
|
||||
"\x00"
|
||||
@ -886,25 +845,21 @@
|
||||
"Right side[um]"
|
||||
"Destra [um]"
|
||||
|
||||
#MSG_SECOND_SERIAL_ON c=17 r=1
|
||||
"RPi port [on]"
|
||||
"Porta RPi [on]"
|
||||
|
||||
#MSG_SECOND_SERIAL_OFF c=17 r=1
|
||||
"RPi port [off]"
|
||||
"Porta RPi [off]"
|
||||
#MSG_RPI_PORT
|
||||
"RPi port"
|
||||
"Porta RPi"
|
||||
|
||||
#MSG_WIZARD_RERUN c=20 r=7
|
||||
"Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
"Se avvi il Wizard perderai la calibrazione preesistente e dovrai ricominciare dall'inizio. Continuare?"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1
|
||||
"SD card [normal]"
|
||||
"Mem. SD [normale]"
|
||||
#MSG_SD_CARD
|
||||
"SD card"
|
||||
"Mem. SD"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1
|
||||
"SD card [flshAir]"
|
||||
"Mem. SD [flshAir]"
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY
|
||||
"FlashAir"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Right"
|
||||
@ -946,10 +901,6 @@
|
||||
"Select nozzle preheat temperature which matches your material."
|
||||
"Selezionate la temperatura per il preriscaldamento dell'ugello adatta al vostro materiale."
|
||||
|
||||
#
|
||||
"Select PLA filament:"
|
||||
"Selezionate filamento PLA:"
|
||||
|
||||
#MSG_SET_TEMPERATURE c=19 r=1
|
||||
"Set temperature:"
|
||||
"Imposta temperatura:"
|
||||
@ -970,49 +921,49 @@
|
||||
"Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
|
||||
"Alcuni file non saranno ordinati. Il numero massimo di file in una cartella e 100 perche siano ordinati."
|
||||
|
||||
#MSG_SORT_NONE c=17 r=1
|
||||
"Sort [none]"
|
||||
"Ordina [none]"
|
||||
#MSG_SORT
|
||||
"Sort"
|
||||
"Ordina"
|
||||
|
||||
#MSG_SORT_TIME c=17 r=1
|
||||
"Sort [time]"
|
||||
"Ordina [time]"
|
||||
#MSG_NONE
|
||||
"None"
|
||||
"Nessuno"
|
||||
|
||||
#MSG_SORT_TIME
|
||||
"Time"
|
||||
"Cron."
|
||||
|
||||
#
|
||||
"Severe skew"
|
||||
"Disassamento grave"
|
||||
"Severe skew:"
|
||||
"Devia.grave:"
|
||||
|
||||
#MSG_SORT_ALPHA c=17 r=1
|
||||
"Sort [alphabet]"
|
||||
"Ordine [alfabet]"
|
||||
#MSG_SORT_ALPHA
|
||||
"Alphabet"
|
||||
"Alfabeti"
|
||||
|
||||
#MSG_SORTING c=20 r=1
|
||||
"Sorting files"
|
||||
"Ordinando i file"
|
||||
|
||||
#MSG_SOUND_LOUD c=17 r=1
|
||||
"Sound [loud]"
|
||||
"Suono [forte]"
|
||||
#MSG_SOUND_LOUD
|
||||
"Loud"
|
||||
"Forte"
|
||||
|
||||
#
|
||||
"Slight skew"
|
||||
"Disassamento lieve"
|
||||
"Slight skew:"
|
||||
"Devia.lieve:"
|
||||
|
||||
#MSG_SOUND_MUTE c=17 r=1
|
||||
"Sound [mute]"
|
||||
"Suono [mute]"
|
||||
#MSG_SOUND
|
||||
"Sound"
|
||||
"Suono"
|
||||
|
||||
#
|
||||
"Some problem encountered, Z-leveling enforced ..."
|
||||
"Sono stati rilevati problemi, avviato livellamento Z ..."
|
||||
|
||||
#MSG_SOUND_ONCE c=17 r=1
|
||||
"Sound [once]"
|
||||
"Suono [singolo]"
|
||||
|
||||
#MSG_SOUND_SILENT c=17 r=1
|
||||
"Sound [silent]"
|
||||
"Suono[silenzioso]"
|
||||
#MSG_SOUND_ONCE
|
||||
"Once"
|
||||
"Singolo"
|
||||
|
||||
#MSG_SPEED
|
||||
"Speed"
|
||||
@ -1046,17 +997,17 @@
|
||||
"Swapped"
|
||||
"Scambiato"
|
||||
|
||||
#MSG_TEMP_CALIBRATION c=20 r=1
|
||||
"Temp. cal. "
|
||||
"Calib. temp. "
|
||||
#
|
||||
"Select filament:"
|
||||
"Seleziona il filamento:"
|
||||
|
||||
#MSG_TEMP_CALIBRATION_ON c=20 r=1
|
||||
"Temp. cal. [on]"
|
||||
"Calib. temp. [ON]"
|
||||
#MSG_TEMP_CALIBRATION c=12 r=1
|
||||
"Temp. cal."
|
||||
"Calib. temp."
|
||||
|
||||
#MSG_TEMP_CALIBRATION_OFF c=20 r=1
|
||||
"Temp. cal. [off]"
|
||||
"Calib. temp.[OFF]"
|
||||
#
|
||||
"Select temperature which matches your material."
|
||||
"Seleziona la temperatura appropriata per il tuo materiale."
|
||||
|
||||
#MSG_CALIBRATION_PINDA_MENU c=17 r=1
|
||||
"Temp. calibration"
|
||||
@ -1088,7 +1039,7 @@
|
||||
|
||||
#
|
||||
"Total print time"
|
||||
"Tempo di stampa totale"
|
||||
"Tempo stampa totale"
|
||||
|
||||
#MSG_TUNE
|
||||
"Tune"
|
||||
@ -1112,7 +1063,7 @@
|
||||
|
||||
#MSG_UNLOAD_FILAMENT c=17
|
||||
"Unload filament"
|
||||
"Scarica filam."
|
||||
"Scarica filamento"
|
||||
|
||||
#MSG_UNLOADING_FILAMENT c=20 r=1
|
||||
"Unloading filament"
|
||||
@ -1234,10 +1185,162 @@
|
||||
"Y distance from min"
|
||||
"Distanza Y dal min"
|
||||
|
||||
#
|
||||
"The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Y-correct:"
|
||||
"Correzione-Y:"
|
||||
|
||||
#MSG_OFF
|
||||
" [off]"
|
||||
"Off"
|
||||
"\x00"
|
||||
|
||||
#MSG_ON
|
||||
"On"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Back"
|
||||
"Indietro"
|
||||
|
||||
#
|
||||
"Checks"
|
||||
"Controlli"
|
||||
|
||||
#
|
||||
"False triggering"
|
||||
"Falso innesco"
|
||||
|
||||
#
|
||||
"FINDA:"
|
||||
"\x00"
|
||||
|
||||
#MSG_FIRMWARE
|
||||
"Firmware"
|
||||
"\x00"
|
||||
|
||||
#MSG_STRICT
|
||||
"Strict"
|
||||
"Esatto"
|
||||
|
||||
#MSG_WARN
|
||||
"Warn"
|
||||
"Avviso"
|
||||
|
||||
#
|
||||
"HW Setup"
|
||||
"Installazione HW"
|
||||
|
||||
#
|
||||
"IR:"
|
||||
"\x00"
|
||||
|
||||
#MSG_MAGNETS_COMP
|
||||
"Magnets comp."
|
||||
"Comp. Magneti"
|
||||
|
||||
#MSG_MESH
|
||||
"Mesh"
|
||||
"Griglia"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Mesh livel. letto"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"Firmware MK3S rilevato su stampante MK3"
|
||||
|
||||
#MSG_MMU_MODE
|
||||
"MMU Mode"
|
||||
"Mod. MMU"
|
||||
|
||||
#
|
||||
"Mode change in progress ..."
|
||||
"Cambio modalita in corso ..."
|
||||
|
||||
#MSG_MODEL
|
||||
"Model"
|
||||
"Modello"
|
||||
|
||||
#MSG_NOZZLE_DIAMETER
|
||||
"Nozzle d."
|
||||
"Diam.Ugello"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Continue?"
|
||||
"G-code processato per un livello diverso. Continuare?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
"G-code processato per un livello diverso. Per favore esegui nuovamente lo slice del modello. Stampa annullata."
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-code processato per una stampante diversa. Continuare?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
"G-code processato per una stampante diversa. Per favore esegui nuovamente lo slice del modello. Stampa annullata."
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Continue?"
|
||||
"G-code processato per un firmware piu recente. Continuare?"
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Please update the firmware. Print cancelled."
|
||||
"G-code processato per un firmware piu recente. Per favore aggiorna il firmware. Stampa annullata."
|
||||
|
||||
#
|
||||
"PINDA:"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Preheating to cut"
|
||||
"Preriscaldamento per taglio"
|
||||
|
||||
#
|
||||
"Preheating to eject"
|
||||
"Preriscaldamento per espulsione"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Continue?"
|
||||
"Diametro ugello diverso da G-Code. Continuare?"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
|
||||
"Diametro ugello diverso dal G-Code. Controlla il valore nelle impostazioni. Stampa annullata."
|
||||
|
||||
#
|
||||
"Rename"
|
||||
"Rinomina"
|
||||
|
||||
#
|
||||
"Select"
|
||||
"Seleziona"
|
||||
|
||||
#
|
||||
"Sensor info"
|
||||
"Info Sensore"
|
||||
|
||||
#
|
||||
"Sheet"
|
||||
"Piano"
|
||||
|
||||
#MSG_SOUND_BLIND
|
||||
"Assist"
|
||||
"Assist."
|
||||
|
||||
#
|
||||
"Steel sheets"
|
||||
"Piani d'acciaio"
|
||||
|
||||
#
|
||||
"Z-correct:"
|
||||
"Correzione-Z:"
|
||||
|
||||
#MSG_Z_PROBE_NR
|
||||
"Z-probe nr."
|
||||
"\x00"
|
||||
|
@ -1,3 +1,7 @@
|
||||
#
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
"[%.7s]Live Adj. Z\x0austaw., kontynuowac\x0aczy zaczac od 0?\x0a%cKontynuuj%cReset"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" z 4"
|
||||
@ -8,7 +12,7 @@
|
||||
|
||||
#MSG_MEASURED_OFFSET
|
||||
"[0;0] point offset"
|
||||
"[0;0] przesuniecie punktu"
|
||||
"[0;0] przesun.punktu"
|
||||
|
||||
#MSG_CRASH_DET_ONLY_IN_NORMAL c=20 r=4
|
||||
"Crash detection can\x0abe turned on only in\x0aNormal mode"
|
||||
@ -24,7 +28,7 @@
|
||||
|
||||
#MSG_BABYSTEPPING_Z c=15
|
||||
"Adjusting Z:"
|
||||
"Dostrajanie Z:"
|
||||
"Ustawianie Z:"
|
||||
|
||||
#MSG_SELFTEST_CHECK_ALLCORRECT c=20
|
||||
"All correct "
|
||||
@ -44,19 +48,11 @@
|
||||
|
||||
#MSG_CONFIRM_CARRIAGE_AT_THE_TOP c=20 r=2
|
||||
"Are left and right Z~carriages all up?"
|
||||
"Obydwa konce osi dojechaly do gornych ogranicznikow?"
|
||||
"Obydwa konce osi sa na szczycie?"
|
||||
|
||||
#MSG_AUTO_DEPLETE_ON c=17 r=1
|
||||
"SpoolJoin [on]"
|
||||
"SpoolJoin [wl]"
|
||||
|
||||
#
|
||||
"SpoolJoin [N/A]"
|
||||
"SpoolJoin [nd]"
|
||||
|
||||
#MSG_AUTO_DEPLETE_OFF c=17 r=1
|
||||
"SpoolJoin [off]"
|
||||
"SpoolJoin [wyl]"
|
||||
#MSG_AUTO_DEPLETE c=17 r=1
|
||||
"SpoolJoin"
|
||||
"\x00"
|
||||
|
||||
#MSG_AUTO_HOME
|
||||
"Auto home"
|
||||
@ -64,11 +60,11 @@
|
||||
|
||||
#MSG_AUTOLOAD_FILAMENT c=17
|
||||
"AutoLoad filament"
|
||||
"AutoLadowanie fil."
|
||||
"Autoladowanie fil."
|
||||
|
||||
#MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4
|
||||
"Autoloading filament available only when filament sensor is turned on..."
|
||||
"Autoladowanie filamentu dostepne tylko gdy czujnik filamentu jest wlaczony..."
|
||||
"Autoladowanie fil. dostepne tylko gdy czujnik filamentu jest wlaczony..."
|
||||
|
||||
#MSG_AUTOLOADING_ENABLED c=20 r=4
|
||||
"Autoloading filament is active, just press the knob and insert filament..."
|
||||
@ -96,7 +92,7 @@
|
||||
|
||||
#MSG_BED_CORRECTION_MENU
|
||||
"Bed level correct"
|
||||
"Korekta poziomowania stolu"
|
||||
"Korekta stolu"
|
||||
|
||||
#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4
|
||||
"Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
|
||||
@ -171,16 +167,12 @@
|
||||
"Skopiowac wybrany jezyk?"
|
||||
|
||||
#MSG_CRASHDETECT_ON
|
||||
"Crash det. [on]"
|
||||
"Wykr.zderzen [wl]"
|
||||
"Crash det."
|
||||
"Wykr.zderzen"
|
||||
|
||||
#MSG_CRASHDETECT_NA
|
||||
"Crash det. [N/A]"
|
||||
"Wykr.zderzen[n/d]"
|
||||
|
||||
#MSG_CRASHDETECT_OFF
|
||||
"Crash det. [off]"
|
||||
"Wykr.zderzen[wyl]"
|
||||
#
|
||||
"Choose a filament for the First Layer Calibration and select it in the on-screen menu."
|
||||
"Wybierz filament do Kalibracji Pierwszej Warstwy i potwierdz w menu ekranowym."
|
||||
|
||||
#MSG_CRASH_DETECTED c=20 r=1
|
||||
"Crash detected."
|
||||
@ -204,7 +196,7 @@
|
||||
|
||||
#MSG_DISABLE_STEPPERS
|
||||
"Disable steppers"
|
||||
"Wylaczenie silnikow"
|
||||
"Wylacz silniki"
|
||||
|
||||
#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."
|
||||
@ -216,16 +208,12 @@
|
||||
|
||||
#MSG_EXTRUDER_CORRECTION c=10
|
||||
"E-correct:"
|
||||
"Korekcja E:"
|
||||
"Korekcja-E:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
"Eject filament"
|
||||
"Wysun filament"
|
||||
|
||||
#
|
||||
"Eject"
|
||||
"Wysun"
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
"Wysuwanie filamentu"
|
||||
@ -256,11 +244,11 @@
|
||||
|
||||
#MSG_SELFTEST_EXTRUDER_FAN_SPEED c=18
|
||||
"Extruder fan:"
|
||||
"Went. ekstrudera:"
|
||||
"WentHotend:"
|
||||
|
||||
#MSG_INFO_EXTRUDER c=15 r=1
|
||||
"Extruder info"
|
||||
"Informacje o ekstruderze"
|
||||
"Ekstruder - info"
|
||||
|
||||
#MSG_MOVE_E
|
||||
"Extruder"
|
||||
@ -270,17 +258,9 @@
|
||||
"Fail stats MMU"
|
||||
"Bledy MMU"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_ON c=17 r=1
|
||||
"F. autoload [on]"
|
||||
"Autolad. fil [wl]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_NA c=17 r=1
|
||||
"F. autoload [N/A]"
|
||||
"Autolad.fil.[N/D]"
|
||||
|
||||
#MSG_FSENS_AUTOLOAD_OFF c=17 r=1
|
||||
"F. autoload [off]"
|
||||
"Autolad.fil.[wyl]"
|
||||
#MSG_FSENSOR_AUTOLOAD
|
||||
"F. autoload"
|
||||
"Autolad. fil."
|
||||
|
||||
#
|
||||
"Fail stats"
|
||||
@ -294,25 +274,13 @@
|
||||
"Fan test"
|
||||
"Test wentylatora"
|
||||
|
||||
#MSG_FANS_CHECK_ON c=17 r=1
|
||||
"Fans check [on]"
|
||||
"Sprawd.went. [wl]"
|
||||
#MSG_FANS_CHECK
|
||||
"Fans check"
|
||||
"Sprawd.went."
|
||||
|
||||
#MSG_FANS_CHECK_OFF c=17 r=1
|
||||
"Fans check [off]"
|
||||
"Sprawd.went.[wyl]"
|
||||
|
||||
#MSG_FSENSOR_ON
|
||||
"Fil. sensor [on]"
|
||||
"Czuj. filam. [wl]"
|
||||
|
||||
#MSG_FSENSOR_NA
|
||||
"Fil. sensor [N/A]"
|
||||
"Czuj. filam.[N/D]"
|
||||
|
||||
#MSG_FSENSOR_OFF
|
||||
"Fil. sensor [off]"
|
||||
"Czuj. filam.[wyl]"
|
||||
#MSG_FSENSOR
|
||||
"Fil. sensor"
|
||||
"Czuj. filam."
|
||||
|
||||
#
|
||||
"Filam. runouts"
|
||||
@ -320,7 +288,7 @@
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
"Filament wychodzi z dyszy a kolor jest czysty?"
|
||||
"Filament wychodzi z dyszy, kolor jest ok?"
|
||||
|
||||
#MSG_NOT_LOADED c=19
|
||||
"Filament not loaded"
|
||||
@ -462,18 +430,10 @@
|
||||
"I will run z calibration now."
|
||||
"Przeprowadze kalibracje Z."
|
||||
|
||||
#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."
|
||||
"Zaczne drukowac linie. Stopniowo opuszczaj dysze przekrecajac pokretlo, poki nie uzyskasz optymalnej wysokosci. Sprawdz obrazki w naszym Podreczniku w rozdz. Kalibracja"
|
||||
|
||||
#MSG_WATCH
|
||||
"Info screen"
|
||||
"Ekran informacyjny"
|
||||
|
||||
#
|
||||
"Is filament 1 loaded?"
|
||||
"Filament 1 zaladowany?"
|
||||
|
||||
#MSG_INSERT_FILAMENT c=20
|
||||
"Insert filament"
|
||||
"Wprowadz filament"
|
||||
@ -482,14 +442,6 @@
|
||||
"Is filament loaded?"
|
||||
"Filament jest zaladowany?"
|
||||
|
||||
#MSG_WIZARD_PLA_FILAMENT c=20 r=2
|
||||
"Is it PLA filament?"
|
||||
"Czy to filament PLA?"
|
||||
|
||||
#MSG_PLA_FILAMENT_LOADED c=20 r=2
|
||||
"Is PLA filament loaded?"
|
||||
"Fialment PLA jest zaladowany?"
|
||||
|
||||
#MSG_STEEL_SHEET_CHECK c=20 r=2
|
||||
"Is steel sheet on heatbed?"
|
||||
"Czy plyta stal. jest na podgrzew. stole?"
|
||||
@ -498,6 +450,10 @@
|
||||
"Last print failures"
|
||||
"Ostatnie bledy druku"
|
||||
|
||||
#
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
"Jesli masz dodatkowe plyty stalowe, to skalibruj ich ustawienia w menu Ustawienia - Ustawienia HW - Plyty stalowe."
|
||||
|
||||
#
|
||||
"Last print"
|
||||
"Ost. wydruk"
|
||||
@ -516,7 +472,7 @@
|
||||
|
||||
#
|
||||
"Lin. correction"
|
||||
"Korekcja lin."
|
||||
"Korekcja liniowa"
|
||||
|
||||
#MSG_BABYSTEP_Z
|
||||
"Live adjust Z"
|
||||
@ -586,13 +542,17 @@
|
||||
"MMU OK. Resuming..."
|
||||
"MMU OK. Wznawianie..."
|
||||
|
||||
#MSG_STEALTH_MODE_OFF
|
||||
"Mode [Normal]"
|
||||
"Tryb [normalny]"
|
||||
#MSG_MODE
|
||||
"Mode"
|
||||
"Tryb"
|
||||
|
||||
#MSG_SILENT_MODE_ON
|
||||
"Mode [silent]"
|
||||
"Tryb [cichy]"
|
||||
#MSG_NORMAL
|
||||
"Normal"
|
||||
"Normalny"
|
||||
|
||||
#MSG_SILENT
|
||||
"Silent"
|
||||
"Cichy"
|
||||
|
||||
#
|
||||
"MMU needs user attention."
|
||||
@ -602,17 +562,17 @@
|
||||
"MMU power fails"
|
||||
"Zaniki zasil. MMU"
|
||||
|
||||
#MSG_STEALTH_MODE_ON
|
||||
"Mode [Stealth]"
|
||||
"Tryb [Stealth]"
|
||||
#MSG_STEALTH
|
||||
"Stealth"
|
||||
"Cichy"
|
||||
|
||||
#MSG_AUTO_MODE_ON
|
||||
"Mode [auto power]"
|
||||
"Tryb [automatycz]"
|
||||
#MSG_AUTO_POWER
|
||||
"Auto power"
|
||||
"Automatycz"
|
||||
|
||||
#MSG_SILENT_MODE_OFF
|
||||
"Mode [high power]"
|
||||
"Tryb[wysoka wyd.]"
|
||||
#MSG_HIGH_POWER
|
||||
"High power"
|
||||
"Wysoka wyd."
|
||||
|
||||
#
|
||||
"MMU2 connected"
|
||||
@ -646,7 +606,7 @@
|
||||
"No SD card"
|
||||
"Brak karty SD"
|
||||
|
||||
#
|
||||
#MSG_NA
|
||||
"N/A"
|
||||
"N/D"
|
||||
|
||||
@ -688,7 +648,7 @@
|
||||
|
||||
#
|
||||
"Nozzle FAN"
|
||||
"Went. hotendu"
|
||||
"WentHotend"
|
||||
|
||||
#MSG_PAUSE_PRINT
|
||||
"Pause print"
|
||||
@ -720,7 +680,7 @@
|
||||
|
||||
#MSG_CONFIRM_NOZZLE_CLEAN c=20 r=8
|
||||
"Please clean the nozzle for calibration. Click when done."
|
||||
"Dla prawidl. kalibracji nalezy oczyscic dysze. Potw. guzikiem."
|
||||
"Dla prawidlowej kalibracji nalezy oczyscic dysze. Potwierdz guzikiem."
|
||||
|
||||
#MSG_SELFTEST_PLEASECHECK
|
||||
"Please check :"
|
||||
@ -730,14 +690,6 @@
|
||||
"Please check our handbook and fix the problem. Then resume the Wizard by rebooting the printer."
|
||||
"Przeczytaj nasz Podrecznik druku 3D aby naprawic problem. Potem wznow Asystenta przez restart drukarki."
|
||||
|
||||
#MSG_WIZARD_LOAD_FILAMENT c=20 r=8
|
||||
"Please insert PLA filament to the extruder, then press knob to load it."
|
||||
"Umiesc filament PLA w ekstruderze i nacisnij pokretlo, aby zaladowac."
|
||||
|
||||
#MSG_PLEASE_LOAD_PLA c=20 r=4
|
||||
"Please load PLA filament first."
|
||||
"Najpierw zaladuj filament PLA."
|
||||
|
||||
#MSG_CHECK_IDLER c=20 r=4
|
||||
"Please open idler and remove filament manually."
|
||||
"Prosze odciagnac dzwignie dociskowa ekstrudera i recznie usunac filament."
|
||||
@ -750,10 +702,6 @@
|
||||
"Please press the knob to unload filament"
|
||||
"Nacisnij pokretlo aby rozladowac filament"
|
||||
|
||||
#
|
||||
"Please insert PLA filament to the first tube of MMU, then press the knob to load it."
|
||||
"Wsun filament PLA do pierwszej rurki MMU i nacisnij pokretlo aby go zaladowac."
|
||||
|
||||
#MSG_PULL_OUT_FILAMENT c=20 r=4
|
||||
"Please pull out filament immediately"
|
||||
"Wyciagnij filament teraz"
|
||||
@ -820,7 +768,7 @@
|
||||
|
||||
#MSG_SELFTEST_PRINT_FAN_SPEED c=18
|
||||
"Print fan:"
|
||||
"Went. wydruku:"
|
||||
"WentWydruk:"
|
||||
|
||||
#MSG_CARD_MENU
|
||||
"Print from SD"
|
||||
@ -840,11 +788,23 @@
|
||||
|
||||
#MSG_FOLLOW_CALIBRATION_FLOW c=20 r=8
|
||||
"Printer has not been calibrated yet. Please follow the manual, chapter First steps, section Calibration flow."
|
||||
"Drukarka nie zostala jeszcze skalibrowana. Kieruj sie Samouczkiem: rozdzial Pierwsze Kroki, sekcja Konfiguracja przed drukowaniem."
|
||||
"Drukarka nie byla jeszcze kalibrowana. Kieruj sie Samouczkiem: rozdzial Pierwsze Kroki, sekcja Konfiguracja przed drukowaniem."
|
||||
|
||||
#
|
||||
"Print FAN"
|
||||
"Went. wydruku"
|
||||
"WentWydruk"
|
||||
|
||||
#
|
||||
"Please insert filament into the extruder, then press the knob to load it."
|
||||
"Wsun filament do ekstrudera i nacisnij pokretlo, aby go zaladowac."
|
||||
|
||||
#
|
||||
"Please insert filament into the first tube of the MMU, then press the knob to load it."
|
||||
"Wsun filament do pierwszego kanalu w MMU2 i nacisnij pokretlo, aby go zaladowac."
|
||||
|
||||
#
|
||||
"Please load filament first."
|
||||
"Najpierw zaladuj filament."
|
||||
|
||||
#MSG_PRUSA3D
|
||||
"prusa3d.com"
|
||||
@ -886,25 +846,21 @@
|
||||
"Right side[um]"
|
||||
"Prawo [um]"
|
||||
|
||||
#MSG_SECOND_SERIAL_ON c=17 r=1
|
||||
"RPi port [on]"
|
||||
"Port RPi [wl]"
|
||||
|
||||
#MSG_SECOND_SERIAL_OFF c=17 r=1
|
||||
"RPi port [off]"
|
||||
"Port RPi [wyl]"
|
||||
#MSG_RPI_PORT
|
||||
"RPi port"
|
||||
"Port RPi"
|
||||
|
||||
#MSG_WIZARD_RERUN c=20 r=7
|
||||
"Running Wizard will delete current calibration results and start from the beginning. Continue?"
|
||||
"Wlaczenie Asystenta usunie obecne dane kalibracyjne i zacznie od poczatku. Kontynuowac?"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1
|
||||
"SD card [normal]"
|
||||
"Karta SD [normal]"
|
||||
#MSG_SD_CARD
|
||||
"SD card"
|
||||
"Karta SD"
|
||||
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1
|
||||
"SD card [flshAir]"
|
||||
"Karta SD[FlshAir]"
|
||||
#MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY
|
||||
"FlashAir"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Right"
|
||||
@ -924,7 +880,7 @@
|
||||
|
||||
#MSG_SELFTEST_START c=20
|
||||
"Self test start "
|
||||
"Rozpoczynanie Selftestu"
|
||||
"Selftest startuje"
|
||||
|
||||
#MSG_SELFTEST
|
||||
"Selftest "
|
||||
@ -932,7 +888,7 @@
|
||||
|
||||
#MSG_SELFTEST_ERROR
|
||||
"Selftest error !"
|
||||
"Blad selftest !"
|
||||
"Blad selftest!"
|
||||
|
||||
#MSG_SELFTEST_FAILED c=20
|
||||
"Selftest failed "
|
||||
@ -946,13 +902,9 @@
|
||||
"Select nozzle preheat temperature which matches your material."
|
||||
"Wybierz temperature grzania dyszy odpowiednia dla materialu."
|
||||
|
||||
#
|
||||
"Select PLA filament:"
|
||||
"Wybierz filament PLA:"
|
||||
|
||||
#MSG_SET_TEMPERATURE c=19 r=1
|
||||
"Set temperature:"
|
||||
"Ustaw. temperatury:"
|
||||
"Ustaw temperature:"
|
||||
|
||||
#MSG_SETTINGS
|
||||
"Settings"
|
||||
@ -970,50 +922,49 @@
|
||||
"Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
|
||||
"Niektore pliki nie zostana posortowane. Max. liczba plikow w 1 folderze = 100."
|
||||
|
||||
#MSG_SORT_NONE c=17 r=1
|
||||
"Sort [none]"
|
||||
"Sortuj [brak]"
|
||||
#MSG_SORT
|
||||
"Sort"
|
||||
"Sortowanie"
|
||||
|
||||
#MSG_SORT_TIME c=17 r=1
|
||||
"Sort [time]"
|
||||
"Sortuj [czas]"
|
||||
#MSG_NONE
|
||||
"None"
|
||||
"Brak"
|
||||
|
||||
#MSG_SORT_TIME
|
||||
"Time"
|
||||
"Czas"
|
||||
|
||||
#
|
||||
"Severe skew"
|
||||
"Znaczny skos"
|
||||
"Severe skew:"
|
||||
"Znaczny skos:"
|
||||
|
||||
#MSG_SORT_ALPHA c=17 r=1
|
||||
"Sort [alphabet]"
|
||||
"Sortuj [alfabet]"
|
||||
#MSG_SORT_ALPHA
|
||||
"Alphabet"
|
||||
"Alfab"
|
||||
|
||||
#MSG_SORTING c=20 r=1
|
||||
"Sorting files"
|
||||
"Sortowanie plikow"
|
||||
|
||||
#MSG_SOUND_LOUD c=17 r=1
|
||||
"Sound [loud]"
|
||||
"Dzwiek [Glosny]"
|
||||
#MSG_SOUND_LOUD
|
||||
"Loud"
|
||||
"Glosny"
|
||||
|
||||
#
|
||||
"Slight skew"
|
||||
"Lekki skos"
|
||||
"Slight skew:"
|
||||
"Lekki skos:"
|
||||
|
||||
#MSG_SOUND_MUTE c=17 r=1
|
||||
"Sound [mute]"
|
||||
"Dzwiek[Wylaczony]"
|
||||
#MSG_SOUND
|
||||
"Sound"
|
||||
"Dzwiek"
|
||||
|
||||
#
|
||||
"Some problem encountered, Z-leveling enforced ..."
|
||||
"Wykryto problem, wymuszono poziomowanie osi Z ..."
|
||||
|
||||
#MSG_SOUND_ONCE c=17 r=1
|
||||
"Sound [once]"
|
||||
"Dzwiek [1-raz]"
|
||||
|
||||
#MSG_SOUND_SILENT c=17 r=1
|
||||
"Sound [silent]"
|
||||
"Dzwiek [Cichy]"
|
||||
"Wykryto problem, wymuszono poziomowanie osi Z."
|
||||
|
||||
#MSG_SOUND_ONCE
|
||||
"Once"
|
||||
"1-raz"
|
||||
#MSG_SPEED
|
||||
"Speed"
|
||||
"Predkosc"
|
||||
@ -1032,7 +983,7 @@
|
||||
|
||||
#MSG_STOP_PRINT
|
||||
"Stop print"
|
||||
"Zatrzymac druk"
|
||||
"Przerwanie druku"
|
||||
|
||||
#MSG_STOPPED
|
||||
"STOPPED. "
|
||||
@ -1046,17 +997,17 @@
|
||||
"Swapped"
|
||||
"Zamieniono"
|
||||
|
||||
#MSG_TEMP_CALIBRATION c=20 r=1
|
||||
"Temp. cal. "
|
||||
#
|
||||
"Select filament:"
|
||||
"Wybierz filament:"
|
||||
|
||||
#MSG_TEMP_CALIBRATION c=12 r=1
|
||||
"Temp. cal."
|
||||
"Kalibracja temp."
|
||||
|
||||
#MSG_TEMP_CALIBRATION_ON c=20 r=1
|
||||
"Temp. cal. [on]"
|
||||
"Kalibr. temp.[wl]"
|
||||
|
||||
#MSG_TEMP_CALIBRATION_OFF c=20 r=1
|
||||
"Temp. cal. [off]"
|
||||
"Kalibr.temp.[wyl]"
|
||||
#
|
||||
"Select temperature which matches your material."
|
||||
"Wybierz temperature, ktora odpowiada Twojemu filamentowi."
|
||||
|
||||
#MSG_CALIBRATION_PINDA_MENU c=17 r=1
|
||||
"Temp. calibration"
|
||||
@ -1084,11 +1035,11 @@
|
||||
|
||||
#
|
||||
"Total filament"
|
||||
"Calkowita dlugosc filamentu"
|
||||
"Zuzycie filamentu"
|
||||
|
||||
#
|
||||
"Total print time"
|
||||
"Calkowity czas druku"
|
||||
"Laczny czas druku"
|
||||
|
||||
#MSG_TUNE
|
||||
"Tune"
|
||||
@ -1200,7 +1151,7 @@
|
||||
|
||||
#
|
||||
"X-correct:"
|
||||
"Korekcja X:"
|
||||
"Korekcja-X:"
|
||||
|
||||
#MSG_BED_SKEW_OFFSET_DETECTION_PERFECT c=20 r=8
|
||||
"XYZ calibration ok. X/Y axes are perpendicular. Congratulations!"
|
||||
@ -1234,10 +1185,162 @@
|
||||
"Y distance from min"
|
||||
"Dystans od 0 w osi Y"
|
||||
|
||||
#
|
||||
"The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Y-correct:"
|
||||
"Korekcja Y:"
|
||||
"Korekcja-Y:"
|
||||
|
||||
#MSG_OFF
|
||||
" [off]"
|
||||
"Off"
|
||||
"Wyl"
|
||||
|
||||
#MSG_ON
|
||||
"On"
|
||||
"Wl"
|
||||
|
||||
#
|
||||
"Back"
|
||||
"Wstecz"
|
||||
|
||||
#
|
||||
"Checks"
|
||||
"Testy"
|
||||
|
||||
#
|
||||
"False triggering"
|
||||
"Falszywy alarm"
|
||||
|
||||
#
|
||||
"FINDA:"
|
||||
"\x00"
|
||||
|
||||
#MSG_FIRMWARE
|
||||
"Firmware"
|
||||
"\x00"
|
||||
|
||||
#MSG_STRICT
|
||||
"Strict"
|
||||
"Restr."
|
||||
|
||||
#MSG_WARN
|
||||
"Warn"
|
||||
"Ostrzez"
|
||||
|
||||
#
|
||||
"HW Setup"
|
||||
"Ustawienia HW"
|
||||
|
||||
#
|
||||
"IR:"
|
||||
"\x00"
|
||||
|
||||
#MSG_MAGNETS_COMP
|
||||
"Magnets comp."
|
||||
"Kor. magnesow"
|
||||
|
||||
#MSG_MESH
|
||||
"Mesh"
|
||||
"Siatka"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Poziomowanie stolu"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"Wykryto firmware MK3S w drukarce MK3"
|
||||
|
||||
#MSG_MMU_MODE
|
||||
"MMU Mode"
|
||||
"Tryb MMU"
|
||||
|
||||
#
|
||||
"Mode change in progress ..."
|
||||
"Trwa zmiana trybu..."
|
||||
|
||||
#MSG_MODEL
|
||||
"Model"
|
||||
"\x00"
|
||||
|
||||
#MSG_NOZZLE_DIAMETER
|
||||
"Nozzle d."
|
||||
"Sr. dyszy"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Continue?"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
"G-code pociety na innym poziomie. Potnij model ponownie. Druk anulowany."
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-code pociety dla innej drukarki. Kontynuowac?"
|
||||
|
||||
#
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
"G-code pociety dla drukarki innego typu. Potnij model ponownie. Druk anulowany."
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Continue?"
|
||||
"G-code pociety dla nowszego firmware. Kontynuowac?"
|
||||
|
||||
#
|
||||
"G-code sliced for a newer firmware. Please update the firmware. Print cancelled."
|
||||
"G-code pociety dla nowszego firmware. Zaktualizuj firmware. Druk anulowany."
|
||||
|
||||
#
|
||||
"PINDA:"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Preheating to cut"
|
||||
"Nagrzewanie do obciecia"
|
||||
|
||||
#
|
||||
"Preheating to eject"
|
||||
"Nagrzewanie do wysuniecia"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Continue?"
|
||||
"Srednica dyszy drukarki rozni sie od tej w G-code. Kontynuowac?"
|
||||
|
||||
#
|
||||
"Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
|
||||
"Srednica dyszy rozni sie od tej w G-code. Sprawdz ustawienia. Druk anulowany."
|
||||
|
||||
#
|
||||
"Rename"
|
||||
"Zmien nazwe"
|
||||
|
||||
#
|
||||
"Select"
|
||||
"Wybierz"
|
||||
|
||||
#
|
||||
"Sensor info"
|
||||
"Info o sensorach"
|
||||
|
||||
#
|
||||
"Sheet"
|
||||
"Plyta"
|
||||
|
||||
#MSG_SOUND_BLIND
|
||||
"Assist"
|
||||
"Asyst."
|
||||
|
||||
#
|
||||
"Steel sheets"
|
||||
"Plyty stalowe"
|
||||
|
||||
#
|
||||
"Z-correct:"
|
||||
"Korekcja-Z:"
|
||||
|
||||
#MSG_Z_PROBE_NR
|
||||
"Z-probe nr."
|
||||
"Ilosc Pomiarow"
|
||||
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
2156
lang/po/new/cs.po
2156
lang/po/new/cs.po
File diff suppressed because it is too large
Load Diff
2169
lang/po/new/de.po
2169
lang/po/new/de.po
File diff suppressed because it is too large
Load Diff
2170
lang/po/new/es.po
2170
lang/po/new/es.po
File diff suppressed because it is too large
Load Diff
2347
lang/po/new/fr.po
2347
lang/po/new/fr.po
File diff suppressed because it is too large
Load Diff
2526
lang/po/new/it.po
2526
lang/po/new/it.po
File diff suppressed because it is too large
Load Diff
2190
lang/po/new/pl.po
2190
lang/po/new/pl.po
File diff suppressed because it is too large
Load Diff
252
lang/translations.md
Normal file
252
lang/translations.md
Normal file
@ -0,0 +1,252 @@
|
||||
# Translations
|
||||
|
||||
## Workflow
|
||||
|
||||
- Build firmware
|
||||
- using `build.sh`
|
||||
- using `PF-build.sh` with a `break` before `# build languages`
|
||||
- change to `lang` folder
|
||||
- check if lang scripts being able to run with `config.sh`
|
||||
- if you get `Arduino main folder: NG` message change in `config.sh` `export ARDUINO=C:/arduino-1.8.5` to `export ARDUINO=<Path to your Arduino IDE folder>`
|
||||
-example: `export ARDUINO=D:/Github/Prusa-Firmware/PF-build-env-1.0.6/windows-64`
|
||||
- run `lang-build.sh en` to create english `lang_en.tmp`, `lang_en.dat` and `lang_en.bin` files
|
||||
- change in `fw-build.sh` `IGNORE_MISSING_TEXT=1` to `IGNORE_MISSING_TEXT=0` so it stops with error and generates `not_used.txt` and `not_tran.txt`
|
||||
- run modified `fw-build.sh`
|
||||
- `not_tran.txt` should be reviewed and added as these are potential missing translations
|
||||
- copy `not_tran.txt` as `lang_add.txt`
|
||||
- check if there are things you don't want to translate or must be modifed
|
||||
- als check that the strings do not start with `spaces` as the scripts doesn't handle these well at this moment.
|
||||
- run `lang-add.sh lang_add.txt` to add the missing translations to `lang_en.txt` and `lang_en_??.txt`
|
||||
- `not_used.txt` should only contain mesages that aren't used in this variant like MK2.5 vs MK3
|
||||
- run `fw-clean.sh` to cleanup firmware related files
|
||||
- delete `not_used.txt` and `not_tran.txt`
|
||||
- run `lang-clean.sh` to cleanup language related files
|
||||
- run `lang-export.sh all` to create PO files for translation these are stored in `/lang/po` folder
|
||||
- Send them to translators and reviewers or
|
||||
- copy these to `/lang/po/new` and
|
||||
- translate these with POEdit the newly added messages
|
||||
- easiest way is to choose `Validate`in POEdit as it shows you `errors` and the `missing transalations` / most likely the newly added at the top.
|
||||
- The new translated files are expected in `/lang/po/new` folder so store the received files these
|
||||
- run `lang-import.sh <language code (iso639-1)>` for each newly translated language
|
||||
- script improvement to import "all" and other things would be great.
|
||||
- Double check if something is missing or faulty
|
||||
- run `lang-build.sh` to to create `lang_en.tmp/.dat/.bin` and `lang_en_??.tmp/.dat/.bin` files
|
||||
- run `fw-build.sh` and check if there are still some messages in `not_tran.txt` that need attention
|
||||
- After approval
|
||||
- run `fw-clean.sh` to cleanup firmware related files
|
||||
- run `lang-clean.sh` to cleanup language related files
|
||||
- change in `fw-build.sh` back to `IGNORE_MISSING_TEXT=1`
|
||||
- remove `break` from `PF-build.sh` script if that has been modified
|
||||
- build your firmware with `build.sh`, `PF-build.sh` or how you normally do it.
|
||||
- Check/Test firmware on printer
|
||||
|
||||
## Code / usage
|
||||
There are 2 modes of operation. If `LANG_MODE==0`, only one language is being used (the default compilation approach from plain Arduino IDE).
|
||||
The reset of this explanation is devoted to `LANG_MODE==1`:
|
||||
|
||||
`language.h`:
|
||||
```C++
|
||||
// section .loc_sec (originaly .progmem0) will be used for localized translated strings
|
||||
#define PROGMEM_I2 __attribute__((section(".loc_sec")))
|
||||
// section .loc_pri (originaly .progmem1) will be used for localized strings in english
|
||||
#define PROGMEM_I1 __attribute__((section(".loc_pri")))
|
||||
// section .noloc (originaly progmem2) will be used for not localized strings in english
|
||||
#define PROGMEM_N1 __attribute__((section(".noloc")))
|
||||
#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)
|
||||
```
|
||||
That explains the macros:
|
||||
- `_i` expands into `lang_get_translation((__extension__({static const char __c[] PROGMEM_I1 = "\xff\xff" s; &__c[0];})))` . Note the two 0xff's in the beginning of the string. `_i` allows for declaring a string directly inplace of C++ code, no string table is used. The downside of this approach is obvious - the compiler is not able/willing to merge duplicit strings into one.
|
||||
- `_T` expands into `lang_get_translation(s)` without the two 0xff's at the beginning. Must be used in conjunction with MSG tables in `messages.h`. Allows to declare a string only once and use many times.
|
||||
- `_N` means not-translated. These strings reside in a different segment of memory.
|
||||
|
||||
The two 0xff's are somehow magically replaced by real string ID's where the translations are available (still don't know where).
|
||||
```C++
|
||||
const char* lang_get_translation(const char* s){
|
||||
if (lang_selected == 0) return s + 2; //primary language selected, return orig. str.
|
||||
if (lang_table == 0) return s + 2; //sec. lang table not found, return orig. str.
|
||||
uint16_t ui = pgm_read_word(((uint16_t*)s)); //read string id
|
||||
if (ui == 0xffff) return s + 2; //translation not found, return orig. str.
|
||||
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) //read first character
|
||||
return s + 2;//zero length string == not translated, return orig. str.
|
||||
return (const char*)((char*)lang_table + ui); //return calculated pointer
|
||||
}
|
||||
```
|
||||
|
||||
## Files
|
||||
|
||||
### `lang_en.txt`
|
||||
```
|
||||
#MSG_CRASH_DET_ONLY_IN_NORMAL c=20 r=4
|
||||
"Crash detection can\x0abe turned on only in\x0aNormal mode"
|
||||
```
|
||||
|
||||
### `lang_en_*.txt`
|
||||
```
|
||||
#MSG_CRASH_DET_ONLY_IN_NORMAL c=20 r=4
|
||||
"Crash detection can\x0abe turned on only in\x0aNormal mode"
|
||||
"Crash detekce muze\x0abyt zapnuta pouze v\x0aNormal modu"
|
||||
```
|
||||
1. a comment - usually a MSG define with number of characters (c) and rows (r)
|
||||
2. English text
|
||||
3. translated text
|
||||
|
||||
### `not_tran.txt`
|
||||
A simple list of strings that are not translated yet.
|
||||
|
||||
### `not_used.txt`
|
||||
A list os strings not currently used in this variant of the firmware or are obsolete.
|
||||
Example: There are MK2.5 specific messages that aren't used when you compile a MK3 variant and vice versa. So be carefull and double check the code if this message is obsolete or just not used due to the chosen variant.
|
||||
|
||||
## Scripts
|
||||
|
||||
### `config.sh`
|
||||
- Checks setup and sets auxiliary env vars used in many other scripts.
|
||||
- Looks for env var `ARDUINO`. If not found/empty, a default `C:/arduino-1.8.5` is used.
|
||||
- Sets env var `CONFIG_OK=1` when all good, otherwise sets `CONFIG_OK=0`
|
||||
|
||||
### `fw-build.sh`
|
||||
Joins firmware HEX and language binaries into one file.
|
||||
|
||||
### `fw-clean.sh`
|
||||
|
||||
### `lang-add.sh`
|
||||
Adds new messages into the dictionary regardless of whether there have been any older versions.
|
||||
|
||||
### `lang-build.sh`
|
||||
Generates lang_xx.bin (language binary files) for the whole firmware build.
|
||||
|
||||
Arguments:
|
||||
- `$1` : language code (`en`, `cz`, `de`, `es`, `fr`, `it`, `pl`) or `all`
|
||||
- empty/no arguments defaults to `all`
|
||||
|
||||
Input: `lang_en.txt` or `lang_en_xx.txt`
|
||||
|
||||
Output: `lang_xx.bin`
|
||||
|
||||
Temporary files: `lang_xx.tmp` and `lang_xx.dat`
|
||||
|
||||
Description of the process:
|
||||
The script first runs `lang-check.py $1` and removes empty lines and comments (and non-translated texts) into `lang_$1.tmp`.
|
||||
The tmp file now contains all translated texts (some of them empty, i.e. "").
|
||||
The tmp file is then transformed into `lang_$1.dat`, which is a simple dump of all texts together, each terminated with a `\x00`.
|
||||
Format of the `bin` file:
|
||||
- 00-01: `A5 5A`
|
||||
- 02-03: `B4 4B`
|
||||
- 04-05: 2B size
|
||||
- 06-07: 2B number of strings
|
||||
- 08-09: 2B checksum
|
||||
- 0A-0B: 2B lang code hex data: basically `en` converted into `ne`, i.e. characters swapped. Only `cz` is changed into `sc` (old `cs` ISO code).
|
||||
- 0C-0D: 2B signature low
|
||||
- 0E-0F: 2B signature high
|
||||
- 10-(10 + 2*number of strings): table of string offsets from the beginning of this file
|
||||
- after the table there are the strings themselves, each terminated with `\x00`
|
||||
|
||||
The signature is composed of 2B number of strings and 2B checksum in lang_en.bin. Signature in lang_en.bin is zero.
|
||||
|
||||
### `lang-check.sh` and `lang-check.py`
|
||||
Both do the same, only lang-check.py is newer, i.e. lang-check.sh is not used anymore.
|
||||
lang-check.py makes a binary comparison between what's in the dictionary and what's in the binary.
|
||||
|
||||
### `lang-clean.sh`
|
||||
Removes all language output files from lang folder. That means deleting:
|
||||
- if [ "$1" = "en" ]; then
|
||||
rm_if_exists lang_$1.tmp
|
||||
else
|
||||
rm_if_exists lang_$1.tmp
|
||||
rm_if_exists lang_en_$1.tmp
|
||||
rm_if_exists lang_en_$1.dif
|
||||
rm_if_exists lang_$1.ofs
|
||||
rm_if_exists lang_$1.txt
|
||||
fi
|
||||
rm_if_exists lang_$1_check.dif
|
||||
rm_if_exists lang_$1.bin
|
||||
rm_if_exists lang_$1.dat
|
||||
rm_if_exists lang_$1_1.tmp
|
||||
rm_if_exists lang_$1_2.tmp
|
||||
|
||||
### `lang-export.sh`
|
||||
Exports PO (gettext) for external translators.
|
||||
|
||||
### `lang-import.sh`
|
||||
Import from PO.
|
||||
|
||||
Arguments:
|
||||
- `$1` : language code (`en`, `cz`, `de`, `es`, `fr`, `it`, `pl`)
|
||||
- empty/no arguments quits the script
|
||||
|
||||
Input files: `<language code>.po` files like `de.po`, `es.po`, etc.
|
||||
|
||||
Input folder: ´/lang/po/new´
|
||||
|
||||
Output files:
|
||||
|
||||
Output foler: ´/lang/po/new´
|
||||
|
||||
Needed improments to scrpit:
|
||||
- add `all` argument
|
||||
- update `replace in <language> translations` to all known special characters the LCD display with Japanese ROM cannot display
|
||||
- move `lang_en_<language code>.txt` to folder `/lang`
|
||||
- cleanup `<language code>_filtered.po`, `<language code>_new.po` and `nonasci.txt`
|
||||
|
||||
### `progmem.sh`
|
||||
|
||||
Examine content of progmem sections (default is progmem1).
|
||||
|
||||
Input:
|
||||
- $OUTDIR/Firmware.ino.elf
|
||||
- $OUTDIR/sketch/*.o (all object files)
|
||||
|
||||
Outputs:
|
||||
- text.sym - formated symbol listing of section '.text'
|
||||
- $PROGMEM.sym - formated symbol listing of section '.progmemX'
|
||||
- $PROGMEM.lss - disassembly listing file
|
||||
- $PROGMEM.hex - variables - hex
|
||||
- $PROGMEM.chr - variables - char escape
|
||||
- $PROGMEM.var - variables - strings
|
||||
- $PROGMEM.txt - text data only (not used)
|
||||
|
||||
Description of process:
|
||||
- check input files
|
||||
- remove output files
|
||||
- list symbol table of section '.text' from output elf file to text.sym (sorted by address)
|
||||
- calculate start and stop address of section '.$PROGMEM'
|
||||
- dump $PROGMEM data in hex format, cut disassembly (keep hex data only) into $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)
|
||||
- convert $PROGMEM.hex to $PROGMEM.chr (prepare string data for character check and conversion)
|
||||
- replace first space with tab
|
||||
- replace second and third space with tab and space
|
||||
- replace all remaining spaces with '\x'
|
||||
- replace all tabs with spaces
|
||||
- convert $PROGMEM.chr to $PROGMEM.var (convert data to text) - a set of special characters is escaped here including `\x0a`
|
||||
|
||||
|
||||
### `textaddr.sh`
|
||||
|
||||
Compiles `progmem1.var` and `lang_en.txt` files to `textaddr.txt` file (mapping of progmem addreses to text idenifiers).
|
||||
|
||||
Description 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
|
||||
|
||||
Input:
|
||||
- progmem1.var
|
||||
- lang_en.txt
|
||||
|
||||
Output:
|
||||
- textaddr.txt
|
||||
|
||||
|
||||
|
||||
update_lang.sh
|
Loading…
Reference in New Issue
Block a user