Merge remote-tracking branch 'upstream/MK3' into MK3_PAT9125_I2C
This commit is contained in:
commit
31b3ad0613
@ -16,8 +16,8 @@ extern uint16_t nPrinterType;
|
||||
extern PGM_P sPrinterName;
|
||||
|
||||
// Firmware version
|
||||
#define FW_VERSION "3.9.0"
|
||||
#define FW_COMMIT_NR 3421
|
||||
#define FW_VERSION "3.9.3"
|
||||
#define FW_COMMIT_NR 3556
|
||||
// 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
|
||||
@ -552,7 +552,7 @@ enum CalibrationStatus
|
||||
// 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_UNLOAD 50
|
||||
#define MIN_Z_FOR_PREHEAT 10
|
||||
|
||||
#include "Configuration_adv.h"
|
||||
|
@ -62,8 +62,19 @@
|
||||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||
#define FAN_KICKSTART_TIME 800
|
||||
|
||||
|
||||
|
||||
/**
|
||||
* Auto-report all at once with M155 S<seconds> C[bitmask] with single timer
|
||||
*
|
||||
* bit 0 = Auto-report temperatures
|
||||
* bit 1 = Auto-report fans
|
||||
* bit 2 = Auto-report position
|
||||
* bit 3 = free
|
||||
* bit 4 = free
|
||||
* bit 5 = free
|
||||
* bit 6 = free
|
||||
* bit 7 = free
|
||||
*/
|
||||
#define AUTO_REPORT
|
||||
|
||||
//===========================================================================
|
||||
//=============================Mechanical Settings===========================
|
||||
@ -376,6 +387,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Include capabilities in M115 output
|
||||
*/
|
||||
#define EXTENDED_CAPABILITIES_REPORT
|
||||
|
||||
//===========================================================================
|
||||
//============================= Define Defines ============================
|
||||
//===========================================================================
|
||||
|
@ -1,5 +1,5 @@
|
||||
#include "Dcodes.h"
|
||||
//#include "Marlin.h"
|
||||
#include "Marlin.h"
|
||||
#include "Configuration.h"
|
||||
#include "language.h"
|
||||
#include "cmdqueue.h"
|
||||
@ -204,7 +204,7 @@ extern float axis_steps_per_unit[NUM_AXIS];
|
||||
*/
|
||||
void dcode__1()
|
||||
{
|
||||
printf_P(PSTR("D-1 - Endless loop\n"));
|
||||
DBG(_N("D-1 - Endless loop\n"));
|
||||
// cli();
|
||||
while (1);
|
||||
}
|
||||
@ -226,9 +226,7 @@ void dcode_0()
|
||||
LOG("D0 - Reset\n");
|
||||
if (code_seen('B')) //bootloader
|
||||
{
|
||||
cli();
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
softReset();
|
||||
}
|
||||
else //reset
|
||||
{
|
||||
@ -252,8 +250,7 @@ void dcode_1()
|
||||
cli();
|
||||
for (int i = 0; i < 8192; i++)
|
||||
eeprom_write_byte((unsigned char*)i, (unsigned char)0xff);
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
softReset();
|
||||
}
|
||||
|
||||
/*!
|
||||
@ -383,7 +380,7 @@ void dcode_4()
|
||||
*/
|
||||
void dcode_5()
|
||||
{
|
||||
printf_P(PSTR("D5 - Read/Write FLASH\n"));
|
||||
puts_P(PSTR("D5 - Read/Write FLASH"));
|
||||
uint32_t address = 0x0000; //default 0x0000
|
||||
uint16_t count = 0x0400; //default 0x0400 (1kb block)
|
||||
if (code_seen('A')) // Address (0x00000-0x3ffff)
|
||||
@ -420,8 +417,7 @@ void dcode_5()
|
||||
boot_dst_addr = (uint32_t)address;
|
||||
boot_src_addr = (uint32_t)(&data);
|
||||
bootapp_print_vars();
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
softReset();
|
||||
}
|
||||
while (count)
|
||||
{
|
||||
@ -467,8 +463,7 @@ void dcode_7()
|
||||
boot_copy_size = (uint16_t)0xc00;
|
||||
boot_src_addr = (uint32_t)0x0003e400;
|
||||
boot_dst_addr = (uint32_t)0x0003f400;
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
softReset();
|
||||
*/
|
||||
}
|
||||
|
||||
@ -486,7 +481,7 @@ void dcode_7()
|
||||
*/
|
||||
void dcode_8()
|
||||
{
|
||||
printf_P(PSTR("D8 - Read/Write PINDA\n"));
|
||||
puts_P(PSTR("D8 - Read/Write PINDA"));
|
||||
uint8_t cal_status = calibration_status_pinda();
|
||||
float temp_pinda = current_temperature_pinda;
|
||||
float offset_z = temp_compensation_pinda_thermistor_offset(temp_pinda);
|
||||
@ -592,7 +587,7 @@ uint16_t dcode_9_ADC_val(uint8_t i)
|
||||
|
||||
void dcode_9()
|
||||
{
|
||||
printf_P(PSTR("D9 - Read/Write ADC\n"));
|
||||
puts_P(PSTR("D9 - Read/Write ADC"));
|
||||
if ((strchr_pointer[1+1] == '?') || (strchr_pointer[1+1] == 0))
|
||||
{
|
||||
for (uint8_t i = 0; i < ADC_CHAN_CNT; i++)
|
||||
@ -789,7 +784,7 @@ extern void st_synchronize();
|
||||
*/
|
||||
void dcode_2130()
|
||||
{
|
||||
printf_P(PSTR("D2130 - TMC2130\n"));
|
||||
puts_P(PSTR("D2130 - TMC2130"));
|
||||
uint8_t axis = 0xff;
|
||||
switch (strchr_pointer[1+4])
|
||||
{
|
||||
|
@ -4,7 +4,7 @@
|
||||
#ifndef MARLIN_H
|
||||
#define MARLIN_H
|
||||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
#include "macros.h"
|
||||
|
||||
#include <math.h>
|
||||
#include <stdio.h>
|
||||
@ -116,7 +116,6 @@ void serial_echopair_P(const char *s_P, unsigned long v);
|
||||
void serialprintPGM(const char *str);
|
||||
|
||||
bool is_buffer_empty();
|
||||
void get_command();
|
||||
void process_commands();
|
||||
void ramming();
|
||||
|
||||
@ -241,23 +240,12 @@ void Stop();
|
||||
bool IsStopped();
|
||||
void finishAndDisableSteppers();
|
||||
|
||||
//put an ASCII command at the end of the current buffer.
|
||||
void enquecommand(const char *cmd, bool from_progmem = false);
|
||||
|
||||
//put an ASCII command at the end of the current buffer, read from flash
|
||||
#define enquecommand_P(cmd) enquecommand(cmd, true)
|
||||
|
||||
//put an ASCII command at the begin of the current buffer
|
||||
void enquecommand_front(const char *cmd, bool from_progmem = false);
|
||||
|
||||
//put an ASCII command at the begin of the current buffer, read from flash
|
||||
#define enquecommand_front_P(cmd) enquecommand_front(cmd, true)
|
||||
|
||||
void repeatcommand_front();
|
||||
|
||||
// Remove all lines from the command queue.
|
||||
void cmdqueue_reset();
|
||||
|
||||
void prepare_arc_move(char isclockwise);
|
||||
void clamp_to_software_endstops(float target[3]);
|
||||
void refresh_cmd_timeout(void);
|
||||
@ -301,6 +289,7 @@ extern float min_pos[3];
|
||||
extern float max_pos[3];
|
||||
extern bool axis_known_position[3];
|
||||
extern int fanSpeed;
|
||||
extern uint8_t newFanSpeed;
|
||||
extern int8_t lcd_change_fil_state;
|
||||
extern float default_retraction;
|
||||
|
||||
@ -492,6 +481,9 @@ void force_high_power_mode(bool start_high_power_section);
|
||||
|
||||
bool gcode_M45(bool onlyZ, int8_t verbosity_level);
|
||||
void gcode_M114();
|
||||
#if (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))
|
||||
void gcode_M123();
|
||||
#endif //FANCHECK and TACH_0 and TACH_1
|
||||
void gcode_M701();
|
||||
|
||||
#define UVLO !(PINE & (1<<4))
|
||||
@ -507,4 +499,6 @@ void load_filament_final_feed();
|
||||
void marlin_wait_for_click();
|
||||
void raise_z_above(float target, bool plan=true);
|
||||
|
||||
extern "C" void softReset();
|
||||
|
||||
#endif
|
||||
|
@ -255,7 +255,7 @@ void MarlinSerial::print(double n, int digits)
|
||||
|
||||
void MarlinSerial::println(void)
|
||||
{
|
||||
print('\r');
|
||||
// print('\r');
|
||||
print('\n');
|
||||
}
|
||||
|
||||
@ -359,7 +359,7 @@ void MarlinSerial::printFloat(double number, uint8_t digits)
|
||||
|
||||
// Print the decimal point, but only if there are digits beyond
|
||||
if (digits > 0)
|
||||
print(".");
|
||||
print('.');
|
||||
|
||||
// Extract digits from the remainder one at a time
|
||||
while (digits-- > 0)
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -767,6 +767,9 @@ uint8_t Sd2Card::waitStartBlock(void) {
|
||||
|
||||
// Toshiba FlashAir support, copied from
|
||||
// https://flashair-developers.com/en/documents/tutorials/arduino/
|
||||
// However, the official website was closed in September 2019.
|
||||
// There is an archived website (written in Japanese).
|
||||
// https://flashair-developers.github.io/website/docs/tutorials/arduino/2.html
|
||||
|
||||
//------------------------------------------------------------------------------
|
||||
/** Perform Extention Read. */
|
||||
@ -774,7 +777,7 @@ uint8_t Sd2Card::readExt(uint32_t arg, uint8_t* dst, uint16_t count) {
|
||||
uint16_t i;
|
||||
|
||||
// send command and argument.
|
||||
if (cardCommand(CMD48, arg)) {
|
||||
if (cardCommand(CMD48, arg) && cardCommand(CMD17, arg)) { // CMD48 for W-03, CMD17 for W-04
|
||||
error(SD_CARD_ERROR_CMD48);
|
||||
goto fail;
|
||||
}
|
||||
|
@ -20,10 +20,10 @@ public:
|
||||
Timer();
|
||||
void start();
|
||||
void stop(){m_isRunning = false;}
|
||||
bool running(){return m_isRunning;}
|
||||
bool running()const {return m_isRunning;}
|
||||
bool expired(T msPeriod);
|
||||
protected:
|
||||
T started(){return m_started;}
|
||||
T started()const {return m_started;}
|
||||
private:
|
||||
bool m_isRunning;
|
||||
T m_started;
|
||||
|
@ -19,7 +19,7 @@ uint16_t adc_sim_mask;
|
||||
|
||||
void adc_init(void)
|
||||
{
|
||||
printf_P(PSTR("adc_init\n"));
|
||||
puts_P(PSTR("adc_init"));
|
||||
adc_sim_mask = 0x00;
|
||||
ADCSRA |= (1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0);
|
||||
ADMUX |= (1 << REFS0);
|
||||
|
@ -1,10 +1,10 @@
|
||||
//backlight.cpp
|
||||
|
||||
#include "backlight.h"
|
||||
#include "macros.h"
|
||||
#include <avr/eeprom.h>
|
||||
#include <Arduino.h>
|
||||
#include "eeprom.h"
|
||||
#include "Marlin.h"
|
||||
#include "pins.h"
|
||||
#include "fastio.h"
|
||||
#include "Timer.h"
|
||||
@ -111,10 +111,10 @@ void backlight_init()
|
||||
|
||||
#else //LCD_BL_PIN
|
||||
|
||||
void force_bl_on(__attribute__((unused)) bool section_start) {}
|
||||
void force_bl_on(bool) {}
|
||||
void backlight_update() {}
|
||||
void backlight_init() {}
|
||||
void backlight_save() {}
|
||||
void backlight_wake(__attribute__((unused)) const uint8_t flashNo) {}
|
||||
void backlight_wake(const uint8_t) {}
|
||||
|
||||
#endif //LCD_BL_PIN
|
||||
#endif //LCD_BL_PIN
|
||||
|
@ -9,6 +9,8 @@
|
||||
extern FILE _uartout;
|
||||
#define uartout (&_uartout)
|
||||
|
||||
extern void softReset();
|
||||
|
||||
void bootapp_print_vars(void)
|
||||
{
|
||||
fprintf_P(uartout, PSTR("boot_src_addr =0x%08lx\n"), boot_src_addr);
|
||||
@ -39,8 +41,7 @@ void bootapp_ram2flash(uint16_t rptr, uint16_t fptr, uint16_t size)
|
||||
boot_src_addr = (uint32_t)rptr;
|
||||
boot_dst_addr = (uint32_t)fptr;
|
||||
bootapp_print_vars();
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
softReset();
|
||||
}
|
||||
|
||||
void bootapp_reboot_user0(uint8_t reserved)
|
||||
@ -50,6 +51,5 @@ void bootapp_reboot_user0(uint8_t reserved)
|
||||
boot_app_flags = BOOT_APP_FLG_USER0;
|
||||
boot_reserved = reserved;
|
||||
bootapp_print_vars();
|
||||
wdt_enable(WDTO_15MS);
|
||||
while(1);
|
||||
softReset();
|
||||
}
|
||||
|
@ -1,4 +1,5 @@
|
||||
#include "Marlin.h"
|
||||
#include "cmdqueue.h"
|
||||
#include "cardreader.h"
|
||||
#include "ultralcd.h"
|
||||
#include "stepper.h"
|
||||
@ -61,9 +62,10 @@ char *createFilename(char *buffer,const dir_t &p) //buffer>12characters
|
||||
|
||||
/**
|
||||
+* Dive into a folder and recurse depth-first to perform a pre-set operation lsAction:
|
||||
+* LS_Count - Add +1 to nrFiles for every file within the parent
|
||||
+* LS_GetFilename - Get the filename of the file indexed by nrFiles
|
||||
+* LS_SerialPrint - Print the full path and size of each file to serial output
|
||||
+* LS_Count - Add +1 to nrFiles for every file within the parent
|
||||
+* LS_GetFilename - Get the filename of the file indexed by nrFiles
|
||||
+* LS_SerialPrint - Print the full path and size of each file to serial output
|
||||
+* LS_SerialPrint_LFN - Print the full path, long filename and size of each file to serial output
|
||||
+*/
|
||||
|
||||
void CardReader::lsDive(const char *prepend, SdFile parent, const char * const match/*=NULL*/) {
|
||||
@ -89,9 +91,13 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
||||
// Serial.print(path);
|
||||
// Get a new directory object using the full path
|
||||
// and dive recursively into it.
|
||||
|
||||
if (lsAction == LS_SerialPrint_LFN)
|
||||
printf_P(PSTR("DIR_ENTER: %s \"%s\"\n"), path, longFilename[0] ? longFilename : lfilename);
|
||||
|
||||
SdFile dir;
|
||||
if (!dir.open(parent, lfilename, O_READ)) {
|
||||
if (lsAction == LS_SerialPrint) {
|
||||
if (lsAction == LS_SerialPrint || lsAction == LS_SerialPrint_LFN) {
|
||||
//SERIAL_ECHO_START();
|
||||
//SERIAL_ECHOPGM(_i("Cannot open subdir"));////MSG_SD_CANT_OPEN_SUBDIR
|
||||
//SERIAL_ECHOLN(lfilename);
|
||||
@ -99,6 +105,9 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
||||
}
|
||||
lsDive(path, dir);
|
||||
// close() is done automatically by destructor of SdFile
|
||||
|
||||
if (lsAction == LS_SerialPrint_LFN)
|
||||
puts_P(PSTR("DIR_EXIT"));
|
||||
}
|
||||
else {
|
||||
uint8_t pn0 = p.name[0];
|
||||
@ -113,12 +122,18 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
||||
nrFiles++;
|
||||
break;
|
||||
|
||||
case LS_SerialPrint_LFN:
|
||||
case LS_SerialPrint:
|
||||
createFilename(filename, p);
|
||||
SERIAL_PROTOCOL(prepend);
|
||||
SERIAL_PROTOCOL(filename);
|
||||
MYSERIAL.write(' ');
|
||||
|
||||
if (lsAction == LS_SerialPrint_LFN)
|
||||
printf_P(PSTR("\"%s\" "), LONGEST_FILENAME);
|
||||
|
||||
SERIAL_PROTOCOLLN(p.fileSize);
|
||||
manage_heater();
|
||||
break;
|
||||
|
||||
case LS_GetFilename:
|
||||
@ -159,9 +174,9 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
|
||||
} // while readDir
|
||||
}
|
||||
|
||||
void CardReader::ls()
|
||||
void CardReader::ls(bool printLFN)
|
||||
{
|
||||
lsAction=LS_SerialPrint;
|
||||
lsAction = printLFN ? LS_SerialPrint_LFN : LS_SerialPrint;
|
||||
//if(lsAction==LS_Count)
|
||||
//nrFiles=0;
|
||||
|
||||
@ -243,6 +258,8 @@ void CardReader::release()
|
||||
{
|
||||
sdprinting = false;
|
||||
cardOK = false;
|
||||
SERIAL_ECHO_START;
|
||||
SERIAL_ECHOLNRPGM(_n("SD card released"));////MSG_SD_CARD_RELEASED
|
||||
}
|
||||
|
||||
void CardReader::startFileprint()
|
||||
@ -424,7 +441,7 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru
|
||||
SERIAL_PROTOCOLLNRPGM(_N("File selected"));////MSG_SD_FILE_SELECTED
|
||||
getfilename(0, fname);
|
||||
lcd_setstatus(longFilename[0] ? longFilename : fname);
|
||||
lcd_setstatus("SD-PRINTING ");
|
||||
lcd_setstatuspgm(PSTR("SD-PRINTING"));
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -475,7 +492,7 @@ void CardReader::removeFile(const char* name)
|
||||
{
|
||||
SERIAL_PROTOCOLPGM("Deletion failed, File: ");
|
||||
SERIAL_PROTOCOL(fname);
|
||||
SERIAL_PROTOCOLLNPGM(".");
|
||||
SERIAL_PROTOCOLLN('.');
|
||||
}
|
||||
|
||||
}
|
||||
@ -496,7 +513,7 @@ void CardReader::getStatus()
|
||||
SERIAL_PROTOCOLLNPGM("Print saved");
|
||||
}
|
||||
else {
|
||||
SERIAL_PROTOCOLLN(longFilename);
|
||||
SERIAL_PROTOCOLLN(LONGEST_FILENAME);
|
||||
SERIAL_PROTOCOLRPGM(_N("SD printing byte "));////MSG_SD_PRINTING_BYTE
|
||||
SERIAL_PROTOCOL(sdpos);
|
||||
SERIAL_PROTOCOL('/');
|
||||
@ -543,7 +560,7 @@ void CardReader::write_command_no_newline(char *buf)
|
||||
{
|
||||
SERIAL_ERROR_START;
|
||||
SERIAL_ERRORLNRPGM(MSG_SD_ERR_WRITE_TO_FILE);
|
||||
MYSERIAL.println("An error while writing to the SD Card.");
|
||||
SERIAL_PROTOCOLLNPGM("An error while writing to the SD Card.");
|
||||
}
|
||||
}
|
||||
|
||||
@ -870,8 +887,7 @@ void CardReader::presort() {
|
||||
for (int column = 0; column < 20; column++) {
|
||||
if (column < (percent / 5))
|
||||
{
|
||||
lcd_set_cursor(column, 2);
|
||||
lcd_print('\x01'); //simple progress bar
|
||||
lcd_putc_at(column, 2, '\x01'); //simple progress bar
|
||||
}
|
||||
}
|
||||
counter++;
|
||||
@ -949,8 +965,7 @@ void CardReader::presort() {
|
||||
#if !SDSORT_USES_RAM //show progresss bar only if slow sorting method is used
|
||||
for (int column = 0; column <= 19; column++)
|
||||
{
|
||||
lcd_set_cursor(column, 2);
|
||||
lcd_print('\x01'); //simple progress bar
|
||||
lcd_putc_at(column, 2, '\x01'); //simple progress bar
|
||||
}
|
||||
_delay(300);
|
||||
lcd_set_degree();
|
||||
|
@ -6,7 +6,7 @@
|
||||
#define MAX_DIR_DEPTH 10
|
||||
|
||||
#include "SdFile.h"
|
||||
enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename};
|
||||
enum LsAction {LS_SerialPrint,LS_SerialPrint_LFN,LS_Count,LS_GetFilename};
|
||||
class CardReader
|
||||
{
|
||||
public:
|
||||
@ -38,7 +38,7 @@ public:
|
||||
uint16_t getWorkDirDepth();
|
||||
|
||||
|
||||
void ls();
|
||||
void ls(bool printLFN);
|
||||
void chdir(const char * relpath);
|
||||
void updir();
|
||||
void setroot();
|
||||
|
@ -18,6 +18,10 @@ int buflen = 0;
|
||||
// Therefore don't remove the command from the queue in the loop() function.
|
||||
bool cmdbuffer_front_already_processed = false;
|
||||
|
||||
// Used for temporarely preventing accidental adding of Serial commands to the queue.
|
||||
// For now only check_file and the fancheck pause use this.
|
||||
bool cmdqueue_serial_disabled = false;
|
||||
|
||||
int serial_count = 0; //index of character read from serial line
|
||||
boolean comment_mode = false;
|
||||
char *strchr_pointer; // just a pointer to find chars in the command string like X, Y, Z, E, etc
|
||||
@ -91,14 +95,19 @@ bool cmdqueue_pop_front()
|
||||
|
||||
void cmdqueue_reset()
|
||||
{
|
||||
bufindr = 0;
|
||||
bufindw = 0;
|
||||
buflen = 0;
|
||||
while (buflen)
|
||||
{
|
||||
// printf_P(PSTR("dumping: \"%s\" of type %hu\n"), cmdbuffer+bufindr+CMDHDRSIZE, CMDBUFFER_CURRENT_TYPE);
|
||||
ClearToSend();
|
||||
cmdqueue_pop_front();
|
||||
}
|
||||
bufindr = 0;
|
||||
bufindw = 0;
|
||||
|
||||
//commands are removed from command queue after process_command() function is finished
|
||||
//reseting command queue and enqueing new commands during some (usually long running) command processing would cause that new commands are immediately removed from queue (or damaged)
|
||||
//this will ensure that all new commands which are enqueued after cmdqueue reset, will be always executed
|
||||
cmdbuffer_front_already_processed = true;
|
||||
cmdbuffer_front_already_processed = true;
|
||||
}
|
||||
|
||||
// How long a string could be pushed to the front of the command queue?
|
||||
@ -390,7 +399,7 @@ void get_command()
|
||||
}
|
||||
|
||||
// start of serial line processing loop
|
||||
while ((MYSERIAL.available() > 0 && !saved_printing) || (MYSERIAL.available() > 0 && isPrintPaused)) { //is print is saved (crash detection or filament detection), dont process data from serial line
|
||||
while (((MYSERIAL.available() > 0 && !saved_printing) || (MYSERIAL.available() > 0 && isPrintPaused)) && !cmdqueue_serial_disabled) { //is print is saved (crash detection or filament detection), dont process data from serial line
|
||||
|
||||
char serial_char = MYSERIAL.read();
|
||||
/* if (selectedSerialPort == 1)
|
||||
@ -582,8 +591,6 @@ void get_command()
|
||||
((serial_char == '#' || serial_char == ':') && comment_mode == false) ||
|
||||
serial_count >= (MAX_CMD_SIZE - 1) || n==-1)
|
||||
{
|
||||
if(card.eof()) break;
|
||||
|
||||
if(serial_char=='#')
|
||||
stop_buffering=true;
|
||||
|
||||
@ -631,6 +638,9 @@ void get_command()
|
||||
|
||||
comment_mode = false; //for new command
|
||||
serial_count = 0; //clear buffer
|
||||
|
||||
if(card.eof()) break;
|
||||
|
||||
// The following line will reserve buffer space if available.
|
||||
if (! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1, true))
|
||||
return;
|
||||
|
@ -35,6 +35,7 @@ extern char cmdbuffer[BUFSIZE * (MAX_CMD_SIZE + 1) + CMDBUFFER_RESERVE_FRONT];
|
||||
extern size_t bufindr;
|
||||
extern int buflen;
|
||||
extern bool cmdbuffer_front_already_processed;
|
||||
extern bool cmdqueue_serial_disabled;
|
||||
|
||||
// Type of a command, which is to be executed right now.
|
||||
#define CMDBUFFER_CURRENT_TYPE (cmdbuffer[bufindr])
|
||||
@ -65,8 +66,8 @@ extern void cmdqueue_dump_to_serial_single_line(int nr, const char *p);
|
||||
extern void cmdqueue_dump_to_serial();
|
||||
#endif /* CMDBUFFER_DEBUG */
|
||||
extern bool cmd_buffer_empty();
|
||||
extern void enquecommand(const char *cmd, bool from_progmem);
|
||||
extern void enquecommand_front(const char *cmd, bool from_progmem);
|
||||
extern void enquecommand(const char *cmd, bool from_progmem = false);
|
||||
extern void enquecommand_front(const char *cmd, bool from_progmem = false);
|
||||
extern void repeatcommand_front();
|
||||
extern bool is_buffer_empty();
|
||||
extern void get_command();
|
||||
@ -74,7 +75,7 @@ extern uint16_t cmdqueue_calc_sd_length();
|
||||
|
||||
// Return True if a character was found
|
||||
static inline bool code_seen(char code) { return (strchr_pointer = strchr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
|
||||
static inline bool code_seen(const char *code) { return (strchr_pointer = strstr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
|
||||
static inline bool code_seen_P(const char *code_PROGMEM) { return (strchr_pointer = strstr_P(CMDBUFFER_CURRENT_STRING, code_PROGMEM)) != NULL; }
|
||||
static inline float code_value() { return strtod(strchr_pointer+1, NULL);}
|
||||
static inline long code_value_long() { return strtol(strchr_pointer+1, NULL, 10); }
|
||||
static inline int16_t code_value_short() { return int16_t(strtol(strchr_pointer+1, NULL, 10)); };
|
||||
|
@ -93,6 +93,10 @@ void eeprom_init()
|
||||
eeprom_switch_to_next_sheet();
|
||||
}
|
||||
check_babystep();
|
||||
|
||||
#ifdef PINDA_TEMP_COMP
|
||||
if (eeprom_read_byte((uint8_t*)EEPROM_PINDA_TEMP_COMPENSATION) == 0xff) eeprom_update_byte((uint8_t *)EEPROM_PINDA_TEMP_COMPENSATION, 0);
|
||||
#endif //PINDA_TEMP_COMP
|
||||
}
|
||||
|
||||
//! @brief Get default sheet name for index
|
||||
|
@ -98,19 +98,9 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00 00 00 00h 0 __S/P__| Filament used in meters | ??? | D3 Ax0ff1 C4
|
||||
| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00 00 00 00h 0 __S/P__| Total print time | ??? | D3 Ax0fed C4
|
||||
| 0x0FE5h 4069 | float | EEPROM_BED_CALIBRATION_CENTER | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fe5 C8
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0FDDh 4061 | float | EEPROM_BED_CALIBRATION_VEC_X | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fdd C8
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0FD5h 4053 | float | EEPROM_BED_CALIBRATION_VEC_Y | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fd5 C8
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0FC5h 4037 | int16 | EEPROM_BED_CALIBRATION_Z_JITTER | ??? | ff ffh 65535 | ??? | ??? | D3 Ax0fc5 C16
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 __P__ | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode: __on__ | G98 | ^
|
||||
| 0x0FC3h 4035 | free | _EEPROM_FREE_NR1_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0fc3 C1
|
||||
@ -129,10 +119,6 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | Toshiba Air: __on__ | ^ | ^
|
||||
| 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | ??? | D3 Ax0fba C1
|
||||
| 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | ??? | D3 Ax0fb0 C10
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal.: __inactive__ | LCD menu | D3 Ax0faf C1
|
||||
| ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal.: __active__ | ^ | ^
|
||||
| 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 00 00h | Bowden length | ??? | D3 Ax0fae C8
|
||||
@ -143,16 +129,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | Power Panic flag: __active__ | ^ | ^
|
||||
| ^ | ^ | ^ | 02h 2 | ^ | Power Panic flag: __???__ | ^ | ^
|
||||
| 0x0F9Dh 3997 | float | EEPROM_UVLO_CURRENT_POSITION | ??? | ffh 255 | Power Panic position | ??? | D3 Ax0f9d C8
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0F95h 3989 | char | EEPROM_FILENAME | ??? | ffh 255 | Power Panic Filename | ??? | D3 Ax0f95 C8
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0F91h 39851 | uint32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Position | ??? | D3 Ax0f91 C4
|
||||
| 0x0F91h 3985 | uint32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Position | ??? | D3 Ax0f91 C4
|
||||
| 0x0F8Dh 3981 | float | EEPROM_UVLO_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power Panic Z Position | ^ | D3 Ax0f8d C4
|
||||
| 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic _unused_ | ^ | D3 Ax0f8c C1
|
||||
| 0x0F8Bh 3979 | uint8 | EEPROM_UVLO_TARGET_BED | ??? | ffh 255 | Power Panic Bed temperature | ^ | D3 Ax0f8b C1
|
||||
@ -161,14 +139,6 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| 0x0F87h 3975 | uint8 | EEPROM_FAN_CHECK_ENABLED | 00h 0 | ??? | Fan Check __disabled__ | LCD menu | D3 Ax0f87 C1
|
||||
| ^ | ^ | ^ | 01h 1 | ffh 255 | Fan Check __enabled__ | ^ | ^
|
||||
| 0x0F75h 3957 | uint16 | EEPROM_UVLO_MESH_BED_LEVELING | ??? | ff ffh 65535 | Power Panic Mesh Bed Leveling | ??? | D3 Ax0f75 C18
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^
|
||||
| 0x0F73h 3955 | uint16 | EEPROM_UVLO_Z_MICROSTEPS | ??? | ff ffh 65535 | Power Panic Z microsteps | ??? | D3 Ax0f73 C2
|
||||
| 0x0F72h 3954 | uint8 | EEPROM_UVLO_E_ABS | ??? | ffh 255 | Power Panic ??? position | ??? | D3 Ax0f72 C1
|
||||
| 0x0F6Eh 3950 | foat | EEPROM_UVLO_CURRENT_POSITION_E | ??? | ff ff ff ffh | Power Panic E position | ??? | D3 Ax0f6e C4
|
||||
@ -203,7 +173,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| 0x0F01h 3841 | uint16 | EEPROM_FERROR_COUNT_TOT | 0000-fffe | ff ffh __S/P__ | Total filament sensor errors | ??? | D3 Ax0f01 C2
|
||||
| 0x0EFFh 3839 | uint16 | EEPROM_POWER_COUNT_TOT | 0000-fffe | ff ffh __S/P__ | Total power failures | ??? | D3 Ax0eff C2
|
||||
| 0x0EFEh 3838 | uint8 | EEPROM_TMC2130_HOME_X_ORIGIN | ??? | ffh 255 | ??? | ??? | D3 Ax0efe C1
|
||||
| 0x0EFDh 3837 | uint8 | EEPROM MC2130_HOME_X_BSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efd C1
|
||||
| 0x0EFDh 3837 | uint8 | EEPROM MC2130_HOME_X_BSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efd C1
|
||||
| 0x0EFCh 3836 | uint8 | EEPROM_TMC2130_HOME_X_FSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efc C1
|
||||
| 0x0EFBh 3835 | uint8 | EEPROM_TMC2130_HOME_Y_ORIGIN | ??? | ffh 255 | ??? | ??? | D3 Ax0efb C1
|
||||
| 0x0EFAh 3834 | uint8 | EEPROM_TMC2130_HOME_Y_BSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efa C1
|
||||
@ -257,28 +227,6 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | MMU2/s cutter: __enabled__ | ^ | ^
|
||||
| ^ | ^ | ^ | 02h 2 | ^ | MMU2/s cutter: __always__ | ^ | ^
|
||||
| 0x0DAE 3502 | uint16 | EEPROM_UVLO_MESH_BED_LEVELING_FULL | ??? | ff ffh 65535 | Power panic Mesh bed leveling points | ??? | D3 Ax0dae C288
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^
|
||||
| 0x0DAD 3501 | uint8 | EEPROM_MBL_TYPE | ??? | ffh 255 | Mesh bed leveling precision _unused atm_ | ??? | D3 Ax0dad C1
|
||||
| 0x0DAC 3500 | bool | EEPROM_MBL_MAGNET_ELIMINATION | 01h 1 | ffh 255 | Mesh bed leveling does: __ignores__ magnets | LCD menu | D3 Ax0dac C1
|
||||
| ^ | ^ | ^ | 00h 0 | ^ | Mesh bed leveling does: __NOT ignores__ magnets | ^ | ^
|
||||
@ -294,9 +242,11 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| ^ | ^ | ^ | 00h 0 | ^ | Check mode for nozzle is: __none__ | ^ | ^
|
||||
| 0x0DA7 3495 | uint8 | EEPROM_NOZZLE_DIAMETER | 28h 40 | ffh 255 | Nozzle diameter is: __40 or 0.40mm__ | LCD menu | D3 Ax0da7 C1
|
||||
| ^ | ^ | ^ | 3ch 60 | ^ | Nozzle diameter is: __60 or 0.60mm__ | ^ | ^
|
||||
| ^ | ^ | ^ | 3ch 80 | ^ | Nozzle diameter is: __80 or 0.80mm__ | ^ | ^
|
||||
| ^ | ^ | ^ | 19h 25 | ^ | Nozzle diameter is: __25 or 0.25mm__ | ^ | ^
|
||||
| 0x0DA5 3493 | uint16 | EEPROM_NOZZLE_DIAMETER_uM | 9001h | ff ffh 65535 | Nozzle diameter is: __400um__ | LCD menu | D3 Ax0da5 C2
|
||||
| ^ | ^ | ^ | 5802h | ^ | Nozzle diameter is: __600um__ | ^ | ^
|
||||
| ^ | ^ | ^ | 2003h | ^ | Nozzle diameter is: __800um__ | ^ | ^
|
||||
| ^ | ^ | ^ | fa00h | ^ | Nozzle diameter is: __250um__ | ^ | ^
|
||||
| 0x0DA4 3492 | uint8 | EEPROM_CHECK_MODEL | 01h 1 | ffh 255 | Check mode for printer model is: __warn__ | LCD menu | D3 Ax0da4 C1
|
||||
| ^ | ^ | ^ | 02h 0 | ^ | Check mode for printer model is: __strict__ | ^ | ^
|
||||
@ -359,8 +309,15 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
|
||||
| ^ | ^ | ^ | 00h 0 | ^ | LCD backlight mode: __Dim__ | ^ | ^
|
||||
| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | 0a 00h 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2
|
||||
| 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4
|
||||
| 0x0D2B 3371 | uint8 | EEPROM_ALTFAN_OVERRIDE | 0-1 | 00h 0 | ALTFAN override | LCD menu | D3 Ax0d2b C1
|
||||
| 0x0D2A 3370 | uint8 | EEPROM_EXPERIMENTAL_VISIBILITY | 0-1 | 00h 0 | Experimental menu visibility | LCD menu | D3 Ax0d2a C1
|
||||
| 0x0D2B 3371 | uint8 | EEPROM_ALTFAN_OVERRIDE | ffh 255 | ffh 255 | ALTFAN override unknown state | LCD menu | D3 Ax0d2b C1
|
||||
| ^ | ^ | ^ | 00h 0 | ^ | ALTFAN override deactivated | ^ | ^
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | ALTFAN override activated | ^ | ^
|
||||
| 0x0D2A 3370 | uint8 | EEPROM_EXPERIMENTAL_VISIBILITY | ffh 255 | ffh 255 | Experimental menu visibility unknown state | LCD menu | D3 Ax0d2a C1
|
||||
| ^ | ^ | ^ | 00h 0 | ^ | Experimental menu visibility hidden | ^ | ^
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | Experimental menu visibility visible | ^ | ^
|
||||
| 0x0D29 3369 | uint8 | EEPROM_PINDA_TEMP_COMPENSATION | ffh 255 | ffh 255 | PINDA temp compensation unknown state | LCD menu | D3 Ax0d29 C1
|
||||
| ^ | ^ | ^ | 00h 0 | ^ | PINDA has no temp compensation PINDA v1/2 | ^ | ^
|
||||
| ^ | ^ | ^ | 01h 1 | ^ | PINDA has temp compensation aka SuperPINDA | ^ | ^
|
||||
|
||||
|
||||
| Address begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code
|
||||
@ -565,9 +522,9 @@ static Sheets * const EEPROM_Sheets_base = (Sheets*)(EEPROM_SHEETS_BASE);
|
||||
|
||||
#define EEPROM_ALTFAN_OVERRIDE (EEPROM_UVLO_LA_K-1) //uint8
|
||||
#define EEPROM_EXPERIMENTAL_VISIBILITY (EEPROM_ALTFAN_OVERRIDE-1) //uint8
|
||||
|
||||
#define EEPROM_PINDA_TEMP_COMPENSATION (EEPROM_EXPERIMENTAL_VISIBILITY-1) //uint8
|
||||
//This is supposed to point to last item to allow EEPROM overrun check. Please update when adding new items.
|
||||
#define EEPROM_LAST_ITEM EEPROM_EXPERIMENTAL_VISIBILITY
|
||||
#define EEPROM_LAST_ITEM EEPROM_PINDA_TEMP_COMPENSATION
|
||||
// !!!!!
|
||||
// !!!!! this is end of EEPROM section ... all updates MUST BE inserted before this mark !!!!!
|
||||
// !!!!!
|
||||
|
@ -7,15 +7,7 @@
|
||||
#define _FASTIO_ARDUINO_H
|
||||
|
||||
#include <avr/io.h>
|
||||
|
||||
/*
|
||||
utility functions
|
||||
*/
|
||||
|
||||
#ifndef MASK
|
||||
/// MASKING- returns \f$2^PIN\f$
|
||||
#define MASK(PIN) (1 << PIN)
|
||||
#endif
|
||||
#include "macros.h"
|
||||
|
||||
#ifndef CRITICAL_SECTION_START
|
||||
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
||||
@ -30,20 +22,20 @@
|
||||
*/
|
||||
|
||||
/// Read a pin
|
||||
#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
|
||||
#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & _BV(DIO ## IO ## _PIN)))
|
||||
/// write to a pin
|
||||
// On some boards pins > 0x100 are used. These are not converted to atomic actions. An critical section is needed.
|
||||
|
||||
#define _WRITE_NC(IO, v) do { if (v) {DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
|
||||
#define _WRITE_NC(IO, v) do { if (v) {DIO ## IO ## _WPORT |= _BV(DIO ## IO ## _PIN); } else {DIO ## IO ## _WPORT &= ~_BV(DIO ## IO ## _PIN); }; } while (0)
|
||||
|
||||
#define _WRITE_C(IO, v) do { if (v) { \
|
||||
CRITICAL_SECTION_START; \
|
||||
{DIO ## IO ## _WPORT |= MASK(DIO ## IO ## _PIN); }\
|
||||
{DIO ## IO ## _WPORT |= _BV(DIO ## IO ## _PIN); }\
|
||||
CRITICAL_SECTION_END; \
|
||||
}\
|
||||
else {\
|
||||
CRITICAL_SECTION_START; \
|
||||
{DIO ## IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }\
|
||||
{DIO ## IO ## _WPORT &= ~_BV(DIO ## IO ## _PIN); }\
|
||||
CRITICAL_SECTION_END; \
|
||||
}\
|
||||
}\
|
||||
@ -52,20 +44,20 @@
|
||||
#define _WRITE(IO, v) do { if (&(DIO ## IO ## _RPORT) >= (uint8_t *)0x100) {_WRITE_C(IO, v); } else {_WRITE_NC(IO, v); }; } while (0)
|
||||
|
||||
/// toggle a pin
|
||||
#define _TOGGLE(IO) do {DIO ## IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0)
|
||||
#define _TOGGLE(IO) do {DIO ## IO ## _RPORT = _BV(DIO ## IO ## _PIN); } while (0)
|
||||
|
||||
/// set pin as input
|
||||
#define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0)
|
||||
#define _SET_INPUT(IO) do {DIO ## IO ## _DDR &= ~_BV(DIO ## IO ## _PIN); } while (0)
|
||||
/// set pin as output
|
||||
#define _SET_OUTPUT(IO) do {DIO ## IO ## _DDR |= MASK(DIO ## IO ## _PIN); } while (0)
|
||||
#define _SET_OUTPUT(IO) do {DIO ## IO ## _DDR |= _BV(DIO ## IO ## _PIN); } while (0)
|
||||
|
||||
/// check if pin is an input
|
||||
#define _GET_INPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) == 0)
|
||||
#define _GET_INPUT(IO) ((DIO ## IO ## _DDR & _BV(DIO ## IO ## _PIN)) == 0)
|
||||
/// check if pin is an output
|
||||
#define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0)
|
||||
#define _GET_OUTPUT(IO) ((DIO ## IO ## _DDR & _BV(DIO ## IO ## _PIN)) != 0)
|
||||
|
||||
/// check if pin is an timer
|
||||
#define _GET_TIMER(IO) ((DIO ## IO ## _PWM)
|
||||
#define _GET_TIMER(IO) (DIO ## IO ## _PWM)
|
||||
|
||||
// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
|
||||
|
||||
|
@ -7,6 +7,7 @@
|
||||
#include "Configuration_prusa.h"
|
||||
#include "language.h"
|
||||
#include "Marlin.h"
|
||||
#include "cmdqueue.h"
|
||||
#include "mmu.h"
|
||||
#include <avr/pgmspace.h>
|
||||
|
||||
|
@ -6,7 +6,6 @@
|
||||
#include <avr/pgmspace.h>
|
||||
#include "pat9125.h"
|
||||
#include "stepper.h"
|
||||
#include "io_atmega2560.h"
|
||||
#include "cmdqueue.h"
|
||||
#include "ultralcd.h"
|
||||
#include "mmu.h"
|
||||
@ -130,7 +129,7 @@ unsigned long nIRsensorLastTime;
|
||||
|
||||
void fsensor_stop_and_save_print(void)
|
||||
{
|
||||
printf_P(PSTR("fsensor_stop_and_save_print\n"));
|
||||
puts_P(PSTR("fsensor_stop_and_save_print"));
|
||||
stop_and_save_print_to_ram(0, 0);
|
||||
fsensor_watch_runout = false;
|
||||
}
|
||||
@ -153,7 +152,7 @@ void fsensor_set_axis_steps_per_unit(float u)
|
||||
|
||||
void fsensor_restore_print_and_continue(void)
|
||||
{
|
||||
printf_P(PSTR("fsensor_restore_print_and_continue\n"));
|
||||
puts_P(PSTR("fsensor_restore_print_and_continue"));
|
||||
fsensor_watch_runout = true;
|
||||
#ifdef PAT9125
|
||||
fsensor_reset_err_cnt();
|
||||
@ -165,7 +164,7 @@ void fsensor_restore_print_and_continue(void)
|
||||
// allowing new instructions to be inserted in the middle
|
||||
void fsensor_checkpoint_print(void)
|
||||
{
|
||||
printf_P(PSTR("fsensor_checkpoint_print\n"));
|
||||
puts_P(PSTR("fsensor_checkpoint_print"));
|
||||
stop_and_save_print_to_ram(0, 0);
|
||||
restore_print_from_ram_and_continue(0);
|
||||
}
|
||||
@ -317,7 +316,7 @@ void fsensor_autoload_check_start(void)
|
||||
printf_P(ERRMSG_PAT9125_NOT_RESP, 3);
|
||||
return;
|
||||
}
|
||||
puts_P(_N("fsensor_autoload_check_start - autoload ENABLED\n"));
|
||||
puts_P(_N("fsensor_autoload_check_start - autoload ENABLED"));
|
||||
fsensor_autoload_y = pat9125_y; //save current y value
|
||||
fsensor_autoload_c = 0; //reset number of changes counter
|
||||
fsensor_autoload_sum = 0;
|
||||
@ -335,7 +334,7 @@ void fsensor_autoload_check_stop(void)
|
||||
if (!fsensor_autoload_enabled) return;
|
||||
// puts_P(_N("fsensor_autoload_check_stop 2\n"));
|
||||
if (!fsensor_watch_autoload) return;
|
||||
puts_P(_N("fsensor_autoload_check_stop - autoload DISABLED\n"));
|
||||
puts_P(_N("fsensor_autoload_check_stop - autoload DISABLED"));
|
||||
fsensor_autoload_sum = 0;
|
||||
fsensor_watch_autoload = false;
|
||||
fsensor_watch_runout = true;
|
||||
@ -415,7 +414,7 @@ void fsensor_oq_meassure_start(uint8_t skip)
|
||||
{
|
||||
if (!fsensor_enabled) return;
|
||||
if (!fsensor_oq_meassure_enabled) return;
|
||||
printf_P(PSTR("fsensor_oq_meassure_start\n"));
|
||||
puts_P(PSTR("fsensor_oq_meassure_start"));
|
||||
fsensor_oq_skipchunk = skip;
|
||||
fsensor_oq_samples = 0;
|
||||
fsensor_oq_st_sum = 0;
|
||||
@ -448,7 +447,7 @@ bool fsensor_oq_result(void)
|
||||
{
|
||||
if (!fsensor_enabled) return true;
|
||||
if (!fsensor_oq_meassure_enabled) return true;
|
||||
printf_P(_N("fsensor_oq_result\n"));
|
||||
puts_P(_N("fsensor_oq_result"));
|
||||
bool res_er_sum = (fsensor_oq_er_sum <= FSENSOR_OQ_MAX_ES);
|
||||
printf_P(_N(" er_sum = %u %S\n"), fsensor_oq_er_sum, (res_er_sum?_OK:_NG));
|
||||
bool res_er_max = (fsensor_oq_er_max <= FSENSOR_OQ_MAX_EM);
|
||||
@ -608,9 +607,8 @@ void fsensor_st_block_chunk(int cnt)
|
||||
if (!fsensor_enabled) return;
|
||||
fsensor_st_cnt += cnt;
|
||||
|
||||
// !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins
|
||||
if (PIN_GET(FSENSOR_INT_PIN)) {PIN_VAL(FSENSOR_INT_PIN, LOW);}
|
||||
else {PIN_VAL(FSENSOR_INT_PIN, HIGH);}
|
||||
// !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins
|
||||
WRITE(FSENSOR_INT_PIN, !READ(FSENSOR_INT_PIN));
|
||||
}
|
||||
#endif //PAT9125
|
||||
|
||||
@ -618,7 +616,7 @@ void fsensor_st_block_chunk(int cnt)
|
||||
//! Common code for enqueing M600 and supplemental codes into the command queue.
|
||||
//! Used both for the IR sensor and the PAT9125
|
||||
void fsensor_enque_M600(){
|
||||
printf_P(PSTR("fsensor_update - M600\n"));
|
||||
puts_P(PSTR("fsensor_update - M600"));
|
||||
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("M600")));
|
||||
@ -672,7 +670,7 @@ void fsensor_update(void)
|
||||
fsensor_softfail_ccnt = 0;
|
||||
if (!err && fsensor_softfail_ccnt <= FSENSOR_SOFTERR_CMAX)
|
||||
{
|
||||
printf_P(PSTR("fsensor_err_cnt = 0\n"));
|
||||
puts_P(PSTR("fsensor_err_cnt = 0"));
|
||||
++fsensor_softfail;
|
||||
++fsensor_softfail_ccnt;
|
||||
fsensor_softfail_last = now;
|
||||
@ -759,19 +757,19 @@ bool fsensor_IR_check(){
|
||||
/// Or the user is so creative so that he can hold a piece of fillament in the hole in such a genius way,
|
||||
/// that the IR fsensor reading is within 1.5 and 3V ... this would have been highly unusual
|
||||
/// and would have been considered more like a sabotage than normal printer operation
|
||||
printf_P(PSTR("fsensor in forbidden range 1.5-3V - check sensor\n"));
|
||||
puts_P(PSTR("fsensor in forbidden range 1.5-3V - check sensor"));
|
||||
return false;
|
||||
}
|
||||
if( oFsensorPCB == ClFsensorPCB::_Rev04 ){
|
||||
/// newer IR sensor cannot normally produce 4.6-5V, this is considered a failure/bad mount
|
||||
if( IRsensor_Hopen_TRESHOLD <= current_voltage_raw_IR && current_voltage_raw_IR <= IRsensor_VMax_TRESHOLD ){
|
||||
printf_P(PSTR("fsensor v0.4 in fault range 4.6-5V - unconnected\n"));
|
||||
puts_P(PSTR("fsensor v0.4 in fault range 4.6-5V - unconnected"));
|
||||
return false;
|
||||
}
|
||||
/// newer IR sensor cannot normally produce 0-0.3V, this is considered a failure
|
||||
#if 0 //Disabled as it has to be decided if we gonna use this or not.
|
||||
if( IRsensor_Hopen_TRESHOLD <= current_voltage_raw_IR && current_voltage_raw_IR <= IRsensor_VMax_TRESHOLD ){
|
||||
printf_P(PSTR("fsensor v0.4 in fault range 0.0-0.3V - wrong IR sensor\n"));
|
||||
puts_P(PSTR("fsensor v0.4 in fault range 0.0-0.3V - wrong IR sensor"));
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
@ -779,7 +777,7 @@ bool fsensor_IR_check(){
|
||||
/// If IR sensor is "uknown state" and filament is not loaded > 1.5V return false
|
||||
#if 0
|
||||
if( (oFsensorPCB == ClFsensorPCB::_Undef) && ( current_voltage_raw_IR > IRsensor_Lmax_TRESHOLD ) ){
|
||||
printf_P(PSTR("Unknown IR sensor version and no filament loaded detected.\n"));
|
||||
puts_P(PSTR("Unknown IR sensor version and no filament loaded detected."));
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
@ -1,6 +1,5 @@
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include "io_atmega2560.h"
|
||||
|
||||
// All this is about silencing the heat bed, as it behaves like a loudspeaker.
|
||||
// Basically, we want the PWM heating switched at 30Hz (or so) which is a well ballanced
|
||||
|
@ -1,374 +0,0 @@
|
||||
//io_atmega2560.h
|
||||
#ifndef _IO_ATMEGA2560
|
||||
#define _IO_ATMEGA2560
|
||||
|
||||
|
||||
#define __PIN_P0 PINE
|
||||
#define __PIN_P1 PINE
|
||||
#define __PIN_P2 PINE
|
||||
#define __PIN_P3 PINE
|
||||
#define __PIN_P4 PING
|
||||
#define __PIN_P5 PINE
|
||||
#define __PIN_P6 PINH
|
||||
#define __PIN_P7 PINH
|
||||
#define __PIN_P8 PINH
|
||||
#define __PIN_P9 PINH
|
||||
#define __PIN_P10 PINB
|
||||
#define __PIN_P11 PINB
|
||||
#define __PIN_P12 PINB
|
||||
#define __PIN_P13 PINB
|
||||
#define __PIN_P14 PINJ
|
||||
#define __PIN_P15 PINJ
|
||||
#define __PIN_P16 PINH
|
||||
#define __PIN_P17 PINH
|
||||
#define __PIN_P18 PIND
|
||||
#define __PIN_P19 PIND
|
||||
#define __PIN_P20 PIND
|
||||
#define __PIN_P21 PIND
|
||||
#define __PIN_P22 PINA
|
||||
#define __PIN_P23 PINA
|
||||
#define __PIN_P24 PINA
|
||||
#define __PIN_P25 PINA
|
||||
#define __PIN_P26 PINA
|
||||
#define __PIN_P27 PINA
|
||||
#define __PIN_P28 PINA
|
||||
#define __PIN_P29 PINA
|
||||
#define __PIN_P30 PINC
|
||||
#define __PIN_P31 PINC
|
||||
#define __PIN_P32 PINC
|
||||
#define __PIN_P33 PINC
|
||||
#define __PIN_P34 PINC
|
||||
#define __PIN_P35 PINC
|
||||
#define __PIN_P36 PINC
|
||||
#define __PIN_P37 PINC
|
||||
#define __PIN_P38 PIND
|
||||
#define __PIN_P39 PING
|
||||
#define __PIN_P40 PING
|
||||
#define __PIN_P41 PING
|
||||
#define __PIN_P42 PINL
|
||||
#define __PIN_P43 PINL
|
||||
#define __PIN_P44 PINL
|
||||
#define __PIN_P45 PINL
|
||||
#define __PIN_P46 PINL
|
||||
#define __PIN_P47 PINL
|
||||
#define __PIN_P48 PINL
|
||||
#define __PIN_P49 PINL
|
||||
#define __PIN_P50 PINB
|
||||
#define __PIN_P51 PINB
|
||||
#define __PIN_P52 PINB
|
||||
#define __PIN_P53 PINB
|
||||
#define __PIN_P54 PINF
|
||||
#define __PIN_P55 PINF
|
||||
#define __PIN_P56 PINF
|
||||
#define __PIN_P57 PINF
|
||||
#define __PIN_P58 PINF
|
||||
#define __PIN_P59 PINF
|
||||
#define __PIN_P60 PINF
|
||||
#define __PIN_P61 PINF
|
||||
#define __PIN_P62 PINK
|
||||
#define __PIN_P63 PINK
|
||||
#define __PIN_P64 PINK
|
||||
#define __PIN_P65 PINK
|
||||
#define __PIN_P66 PINK
|
||||
#define __PIN_P67 PINK
|
||||
#define __PIN_P68 PINK
|
||||
#define __PIN_P69 PINK
|
||||
#define __PIN_P70 PING
|
||||
#define __PIN_P71 PING
|
||||
#define __PIN_P72 PINJ
|
||||
#define __PIN_P73 PINJ
|
||||
#define __PIN_P74 PINJ
|
||||
#define __PIN_P75 PINJ
|
||||
#define __PIN_P76 PINJ
|
||||
#define __PIN_P77 PINJ
|
||||
#define __PIN_P78 PINE
|
||||
#define __PIN_P79 PINE
|
||||
#define __PIN_P80 PINE
|
||||
#define __PIN_P81 PIND
|
||||
#define __PIN_P82 PIND
|
||||
#define __PIN_P83 PIND
|
||||
#define __PIN_P84 PINH
|
||||
#define __PIN_P85 PINH
|
||||
|
||||
#define __PORT_P0 PORTE
|
||||
#define __PORT_P1 PORTE
|
||||
#define __PORT_P2 PORTE
|
||||
#define __PORT_P3 PORTE
|
||||
#define __PORT_P4 PORTG
|
||||
#define __PORT_P5 PORTE
|
||||
#define __PORT_P6 PORTH
|
||||
#define __PORT_P7 PORTH
|
||||
#define __PORT_P8 PORTH
|
||||
#define __PORT_P9 PORTH
|
||||
#define __PORT_P10 PORTB
|
||||
#define __PORT_P11 PORTB
|
||||
#define __PORT_P12 PORTB
|
||||
#define __PORT_P13 PORTB
|
||||
#define __PORT_P14 PORTJ
|
||||
#define __PORT_P15 PORTJ
|
||||
#define __PORT_P16 PORTH
|
||||
#define __PORT_P17 PORTH
|
||||
#define __PORT_P18 PORTD
|
||||
#define __PORT_P19 PORTD
|
||||
#define __PORT_P20 PORTD
|
||||
#define __PORT_P21 PORTD
|
||||
#define __PORT_P22 PORTA
|
||||
#define __PORT_P23 PORTA
|
||||
#define __PORT_P24 PORTA
|
||||
#define __PORT_P25 PORTA
|
||||
#define __PORT_P26 PORTA
|
||||
#define __PORT_P27 PORTA
|
||||
#define __PORT_P28 PORTA
|
||||
#define __PORT_P29 PORTA
|
||||
#define __PORT_P30 PORTC
|
||||
#define __PORT_P31 PORTC
|
||||
#define __PORT_P32 PORTC
|
||||
#define __PORT_P33 PORTC
|
||||
#define __PORT_P34 PORTC
|
||||
#define __PORT_P35 PORTC
|
||||
#define __PORT_P36 PORTC
|
||||
#define __PORT_P37 PORTC
|
||||
#define __PORT_P38 PORTD
|
||||
#define __PORT_P39 PORTG
|
||||
#define __PORT_P40 PORTG
|
||||
#define __PORT_P41 PORTG
|
||||
#define __PORT_P42 PORTL
|
||||
#define __PORT_P43 PORTL
|
||||
#define __PORT_P44 PORTL
|
||||
#define __PORT_P45 PORTL
|
||||
#define __PORT_P46 PORTL
|
||||
#define __PORT_P47 PORTL
|
||||
#define __PORT_P48 PORTL
|
||||
#define __PORT_P49 PORTL
|
||||
#define __PORT_P50 PORTB
|
||||
#define __PORT_P51 PORTB
|
||||
#define __PORT_P52 PORTB
|
||||
#define __PORT_P53 PORTB
|
||||
#define __PORT_P54 PORTF
|
||||
#define __PORT_P55 PORTF
|
||||
#define __PORT_P56 PORTF
|
||||
#define __PORT_P57 PORTF
|
||||
#define __PORT_P58 PORTF
|
||||
#define __PORT_P59 PORTF
|
||||
#define __PORT_P60 PORTF
|
||||
#define __PORT_P61 PORTF
|
||||
#define __PORT_P62 PORTK
|
||||
#define __PORT_P63 PORTK
|
||||
#define __PORT_P64 PORTK
|
||||
#define __PORT_P65 PORTK
|
||||
#define __PORT_P66 PORTK
|
||||
#define __PORT_P67 PORTK
|
||||
#define __PORT_P68 PORTK
|
||||
#define __PORT_P69 PORTK
|
||||
#define __PORT_P70 PORTG
|
||||
#define __PORT_P71 PORTG
|
||||
#define __PORT_P72 PORTJ
|
||||
#define __PORT_P73 PORTJ
|
||||
#define __PORT_P74 PORTJ
|
||||
#define __PORT_P75 PORTJ
|
||||
#define __PORT_P76 PORTJ
|
||||
#define __PORT_P77 PORTJ
|
||||
#define __PORT_P78 PORTE
|
||||
#define __PORT_P79 PORTE
|
||||
#define __PORT_P80 PORTE
|
||||
#define __PORT_P81 PORTD
|
||||
#define __PORT_P82 PORTD
|
||||
#define __PORT_P83 PORTD
|
||||
#define __PORT_P84 PORTH
|
||||
#define __PORT_P85 PORTH
|
||||
|
||||
#define __DDR_P0 DDRE
|
||||
#define __DDR_P1 DDRE
|
||||
#define __DDR_P2 DDRE
|
||||
#define __DDR_P3 DDRE
|
||||
#define __DDR_P4 DDRG
|
||||
#define __DDR_P5 DDRE
|
||||
#define __DDR_P6 DDRH
|
||||
#define __DDR_P7 DDRH
|
||||
#define __DDR_P8 DDRH
|
||||
#define __DDR_P9 DDRH
|
||||
#define __DDR_P10 DDRB
|
||||
#define __DDR_P11 DDRB
|
||||
#define __DDR_P12 DDRB
|
||||
#define __DDR_P13 DDRB
|
||||
#define __DDR_P14 DDRJ
|
||||
#define __DDR_P15 DDRJ
|
||||
#define __DDR_P16 DDRH
|
||||
#define __DDR_P17 DDRH
|
||||
#define __DDR_P18 DDRD
|
||||
#define __DDR_P19 DDRD
|
||||
#define __DDR_P20 DDRD
|
||||
#define __DDR_P21 DDRD
|
||||
#define __DDR_P22 DDRA
|
||||
#define __DDR_P23 DDRA
|
||||
#define __DDR_P24 DDRA
|
||||
#define __DDR_P25 DDRA
|
||||
#define __DDR_P26 DDRA
|
||||
#define __DDR_P27 DDRA
|
||||
#define __DDR_P28 DDRA
|
||||
#define __DDR_P29 DDRA
|
||||
#define __DDR_P30 DDRC
|
||||
#define __DDR_P31 DDRC
|
||||
#define __DDR_P32 DDRC
|
||||
#define __DDR_P33 DDRC
|
||||
#define __DDR_P34 DDRC
|
||||
#define __DDR_P35 DDRC
|
||||
#define __DDR_P36 DDRC
|
||||
#define __DDR_P37 DDRC
|
||||
#define __DDR_P38 DDRD
|
||||
#define __DDR_P39 DDRG
|
||||
#define __DDR_P40 DDRG
|
||||
#define __DDR_P41 DDRG
|
||||
#define __DDR_P42 DDRL
|
||||
#define __DDR_P43 DDRL
|
||||
#define __DDR_P44 DDRL
|
||||
#define __DDR_P45 DDRL
|
||||
#define __DDR_P46 DDRL
|
||||
#define __DDR_P47 DDRL
|
||||
#define __DDR_P48 DDRL
|
||||
#define __DDR_P49 DDRL
|
||||
#define __DDR_P50 DDRB
|
||||
#define __DDR_P51 DDRB
|
||||
#define __DDR_P52 DDRB
|
||||
#define __DDR_P53 DDRB
|
||||
#define __DDR_P54 DDRF
|
||||
#define __DDR_P55 DDRF
|
||||
#define __DDR_P56 DDRF
|
||||
#define __DDR_P57 DDRF
|
||||
#define __DDR_P58 DDRF
|
||||
#define __DDR_P59 DDRF
|
||||
#define __DDR_P60 DDRF
|
||||
#define __DDR_P61 DDRF
|
||||
#define __DDR_P62 DDRK
|
||||
#define __DDR_P63 DDRK
|
||||
#define __DDR_P64 DDRK
|
||||
#define __DDR_P65 DDRK
|
||||
#define __DDR_P66 DDRK
|
||||
#define __DDR_P67 DDRK
|
||||
#define __DDR_P68 DDRK
|
||||
#define __DDR_P69 DDRK
|
||||
#define __DDR_P70 DDRG
|
||||
#define __DDR_P71 DDRG
|
||||
#define __DDR_P72 DDRJ
|
||||
#define __DDR_P73 DDRJ
|
||||
#define __DDR_P74 DDRJ
|
||||
#define __DDR_P75 DDRJ
|
||||
#define __DDR_P76 DDRJ
|
||||
#define __DDR_P77 DDRJ
|
||||
#define __DDR_P78 DDRE
|
||||
#define __DDR_P79 DDRE
|
||||
#define __DDR_P80 DDRE
|
||||
#define __DDR_P81 DDRD
|
||||
#define __DDR_P82 DDRD
|
||||
#define __DDR_P83 DDRD
|
||||
#define __DDR_P84 DDRH
|
||||
#define __DDR_P85 DDRH
|
||||
|
||||
#define __BIT_P0 0
|
||||
#define __BIT_P1 1
|
||||
#define __BIT_P2 4
|
||||
#define __BIT_P3 5
|
||||
#define __BIT_P4 5
|
||||
#define __BIT_P5 3
|
||||
#define __BIT_P6 3
|
||||
#define __BIT_P7 4
|
||||
#define __BIT_P8 5
|
||||
#define __BIT_P9 6
|
||||
#define __BIT_P10 4
|
||||
#define __BIT_P11 5
|
||||
#define __BIT_P12 6
|
||||
#define __BIT_P13 7
|
||||
#define __BIT_P14 1
|
||||
#define __BIT_P15 0
|
||||
#define __BIT_P16 0
|
||||
#define __BIT_P17 1
|
||||
#define __BIT_P18 3
|
||||
#define __BIT_P19 2
|
||||
#define __BIT_P20 1
|
||||
#define __BIT_P21 0
|
||||
#define __BIT_P22 0
|
||||
#define __BIT_P23 1
|
||||
#define __BIT_P24 2
|
||||
#define __BIT_P25 3
|
||||
#define __BIT_P26 4
|
||||
#define __BIT_P27 5
|
||||
#define __BIT_P28 6
|
||||
#define __BIT_P29 7
|
||||
#define __BIT_P30 7
|
||||
#define __BIT_P31 6
|
||||
#define __BIT_P32 5
|
||||
#define __BIT_P33 4
|
||||
#define __BIT_P34 3
|
||||
#define __BIT_P35 2
|
||||
#define __BIT_P36 1
|
||||
#define __BIT_P37 0
|
||||
#define __BIT_P38 7
|
||||
#define __BIT_P39 2
|
||||
#define __BIT_P40 1
|
||||
#define __BIT_P41 0
|
||||
#define __BIT_P42 7
|
||||
#define __BIT_P43 6
|
||||
#define __BIT_P44 5
|
||||
#define __BIT_P45 4
|
||||
#define __BIT_P46 3
|
||||
#define __BIT_P47 2
|
||||
#define __BIT_P48 1
|
||||
#define __BIT_P49 0
|
||||
#define __BIT_P50 3
|
||||
#define __BIT_P51 2
|
||||
#define __BIT_P52 1
|
||||
#define __BIT_P53 0
|
||||
#define __BIT_P54 0
|
||||
#define __BIT_P55 1
|
||||
#define __BIT_P56 2
|
||||
#define __BIT_P57 3
|
||||
#define __BIT_P58 4
|
||||
#define __BIT_P59 5
|
||||
#define __BIT_P60 6
|
||||
#define __BIT_P61 7
|
||||
#define __BIT_P62 0
|
||||
#define __BIT_P63 1
|
||||
#define __BIT_P64 2
|
||||
#define __BIT_P65 3
|
||||
#define __BIT_P66 4
|
||||
#define __BIT_P67 5
|
||||
#define __BIT_P68 6
|
||||
#define __BIT_P69 7
|
||||
#define __BIT_P70 4
|
||||
#define __BIT_P71 3
|
||||
#define __BIT_P72 2
|
||||
#define __BIT_P73 3
|
||||
#define __BIT_P74 7
|
||||
#define __BIT_P75 4
|
||||
#define __BIT_P76 5
|
||||
#define __BIT_P77 6
|
||||
#define __BIT_P78 2
|
||||
#define __BIT_P79 6
|
||||
#define __BIT_P80 7
|
||||
#define __BIT_P81 4
|
||||
#define __BIT_P82 5
|
||||
#define __BIT_P83 6
|
||||
#define __BIT_P84 2
|
||||
#define __BIT_P85 7
|
||||
|
||||
#define __BIT(pin) __BIT_P##pin
|
||||
#define __MSK(pin) (1 << __BIT(pin))
|
||||
|
||||
#define __PIN(pin) __PIN_P##pin
|
||||
#define __PORT(pin) __PORT_P##pin
|
||||
#define __DDR(pin) __DDR_P##pin
|
||||
|
||||
#define PIN(pin) __PIN(pin)
|
||||
#define PORT(pin) __PORT(pin)
|
||||
#define DDR(pin) __DDR(pin)
|
||||
|
||||
#define PIN_INP(pin) DDR(pin) &= ~__MSK(pin)
|
||||
#define PIN_OUT(pin) DDR(pin) |= __MSK(pin)
|
||||
#define PIN_CLR(pin) PORT(pin) &= ~__MSK(pin)
|
||||
#define PIN_SET(pin) PORT(pin) |= __MSK(pin)
|
||||
#define PIN_VAL(pin, val) if (val) PIN_SET(pin); else PIN_CLR(pin);
|
||||
#define PIN_GET(pin) (PIN(pin) & __MSK(pin))
|
||||
#define PIN_INQ(pin) (PORT(pin) & __MSK(pin))
|
||||
|
||||
|
||||
#endif //_IO_ATMEGA2560
|
@ -38,7 +38,7 @@ void la10c_mode_change(LA10C_MODE mode)
|
||||
// Approximate a LA10 value to a LA15 equivalent.
|
||||
static float la10c_convert(float k)
|
||||
{
|
||||
float new_K = k * 0.004 - 0.05;
|
||||
float new_K = k * 0.002 - 0.01;
|
||||
return new_K < 0? 0:
|
||||
new_K > (LA_K_MAX - FLT_EPSILON)? (LA_K_MAX - FLT_EPSILON):
|
||||
new_K;
|
||||
|
@ -17,10 +17,10 @@ uint8_t lang_selected = 0;
|
||||
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
|
||||
uint8_t lang_select(__attribute__((unused)) uint8_t lang) { return 0; }
|
||||
uint8_t lang_select(_UNUSED uint8_t lang) { return 0; }
|
||||
uint8_t lang_get_count() { return 1; }
|
||||
uint16_t lang_get_code(__attribute__((unused)) uint8_t lang) { return LANG_CODE_EN; }
|
||||
const char* lang_get_name_by_code(__attribute__((unused)) uint16_t code) { return _n("English"); }
|
||||
uint16_t lang_get_code(_UNUSED uint8_t lang) { return LANG_CODE_EN; }
|
||||
const char* lang_get_name_by_code(_UNUSED uint16_t code) { return _n("English"); }
|
||||
void lang_reset(void) { }
|
||||
uint8_t lang_is_selected(void) { return 1; }
|
||||
|
||||
|
@ -5,6 +5,7 @@
|
||||
|
||||
|
||||
#include "config.h"
|
||||
#include "macros.h"
|
||||
#include <inttypes.h>
|
||||
#ifdef DEBUG_SEC_LANG
|
||||
#include <stdio.h>
|
||||
@ -22,9 +23,6 @@
|
||||
|
||||
#define MSG_FW_VERSION "Firmware"
|
||||
|
||||
#define STRINGIFY_(n) #n
|
||||
#define STRINGIFY(n) STRINGIFY_(n)
|
||||
|
||||
#if (LANG_MODE == 0) //primary language only
|
||||
#define PROGMEM_I2 __attribute__((section(".progmem0")))
|
||||
#define PROGMEM_I1 __attribute__((section(".progmem1")))
|
||||
|
@ -486,11 +486,17 @@ void lcd_escape_write(uint8_t chr)
|
||||
#endif //VT100
|
||||
|
||||
|
||||
int lcd_putc(int c)
|
||||
int lcd_putc(char c)
|
||||
{
|
||||
return fputc(c, lcdout);
|
||||
}
|
||||
|
||||
int lcd_putc_at(uint8_t c, uint8_t r, char ch)
|
||||
{
|
||||
lcd_set_cursor(c, r);
|
||||
return fputc(ch, lcdout);
|
||||
}
|
||||
|
||||
int lcd_puts_P(const char* str)
|
||||
{
|
||||
return fputs_P(str, lcdout);
|
||||
|
@ -40,7 +40,10 @@ extern void lcd_set_cursor(uint8_t col, uint8_t row);
|
||||
extern void lcd_createChar_P(uint8_t, const uint8_t*);
|
||||
|
||||
|
||||
extern int lcd_putc(int c);
|
||||
// char c is non-standard, however it saves 1B on stack
|
||||
extern int lcd_putc(char c);
|
||||
extern int lcd_putc_at(uint8_t c, uint8_t r, char ch);
|
||||
|
||||
extern int lcd_puts_P(const char* str);
|
||||
extern int lcd_puts_at_P(uint8_t c, uint8_t r, const char* str);
|
||||
extern int lcd_printf_P(const char* format, ...);
|
||||
|
90
Firmware/macros.h
Normal file
90
Firmware/macros.h
Normal file
@ -0,0 +1,90 @@
|
||||
#ifndef MACROS_H
|
||||
#define MACROS_H
|
||||
|
||||
#include <avr/interrupt.h> //for cli() and sei()
|
||||
|
||||
#define FORCE_INLINE __attribute__((always_inline)) inline
|
||||
#define _UNUSED __attribute__((unused))
|
||||
|
||||
#ifndef CRITICAL_SECTION_START
|
||||
#define CRITICAL_SECTION_START unsigned char _sreg = SREG; cli();
|
||||
#define CRITICAL_SECTION_END SREG = _sreg;
|
||||
#endif //CRITICAL_SECTION_START
|
||||
|
||||
// Macros to make a string from a macro
|
||||
#define STRINGIFY_(M) #M
|
||||
#define STRINGIFY(M) STRINGIFY_(M)
|
||||
|
||||
// Macros for bit masks
|
||||
#undef _BV
|
||||
#define _BV(n) (1<<(n))
|
||||
#define TEST(n,b) (!!((n)&_BV(b)))
|
||||
#define SET_BIT_TO(N,B,TF) do{ if (TF) SBI(N,B); else CBI(N,B); }while(0)
|
||||
|
||||
#ifndef SBI
|
||||
#define SBI(A,B) (A |= (1 << (B)))
|
||||
#endif
|
||||
|
||||
#ifndef CBI
|
||||
#define CBI(A,B) (A &= ~(1 << (B)))
|
||||
#endif
|
||||
|
||||
#define TBI(N,B) (N ^= _BV(B))
|
||||
|
||||
|
||||
// Macros to chain up to 12 conditions
|
||||
#define _DO_1(W,C,A) (_##W##_1(A))
|
||||
#define _DO_2(W,C,A,B) (_##W##_1(A) C _##W##_1(B))
|
||||
#define _DO_3(W,C,A,V...) (_##W##_1(A) C _DO_2(W,C,V))
|
||||
#define _DO_4(W,C,A,V...) (_##W##_1(A) C _DO_3(W,C,V))
|
||||
#define _DO_5(W,C,A,V...) (_##W##_1(A) C _DO_4(W,C,V))
|
||||
#define _DO_6(W,C,A,V...) (_##W##_1(A) C _DO_5(W,C,V))
|
||||
#define _DO_7(W,C,A,V...) (_##W##_1(A) C _DO_6(W,C,V))
|
||||
#define _DO_8(W,C,A,V...) (_##W##_1(A) C _DO_7(W,C,V))
|
||||
#define _DO_9(W,C,A,V...) (_##W##_1(A) C _DO_8(W,C,V))
|
||||
#define _DO_10(W,C,A,V...) (_##W##_1(A) C _DO_9(W,C,V))
|
||||
#define _DO_11(W,C,A,V...) (_##W##_1(A) C _DO_10(W,C,V))
|
||||
#define _DO_12(W,C,A,V...) (_##W##_1(A) C _DO_11(W,C,V))
|
||||
#define __DO_N(W,C,N,V...) _DO_##N(W,C,V)
|
||||
#define _DO_N(W,C,N,V...) __DO_N(W,C,N,V)
|
||||
#define DO(W,C,V...) _DO_N(W,C,NUM_ARGS(V),V)
|
||||
|
||||
// Macros to support option testing
|
||||
#define _CAT(a,V...) a##V
|
||||
#define CAT(a,V...) _CAT(a,V)
|
||||
|
||||
#define _ISENA_ ~,1
|
||||
#define _ISENA_1 ~,1
|
||||
#define _ISENA_0x1 ~,1
|
||||
#define _ISENA_true ~,1
|
||||
#define _ISENA(V...) IS_PROBE(V)
|
||||
|
||||
#define _ENA_1(O) _ISENA(CAT(_IS,CAT(ENA_, O)))
|
||||
#define _DIS_1(O) NOT(_ENA_1(O))
|
||||
#define ENABLED(V...) DO(ENA,&&,V)
|
||||
#define DISABLED(V...) DO(DIS,&&,V)
|
||||
|
||||
#define TERN(O,A,B) _TERN(_ENA_1(O),B,A) // OPTION converted to '0' or '1'
|
||||
#define TERN0(O,A) _TERN(_ENA_1(O),0,A) // OPTION converted to A or '0'
|
||||
#define TERN1(O,A) _TERN(_ENA_1(O),1,A) // OPTION converted to A or '1'
|
||||
#define TERN_(O,A) _TERN(_ENA_1(O),,A) // OPTION converted to A or '<nul>'
|
||||
#define _TERN(E,V...) __TERN(_CAT(T_,E),V) // Prepend 'T_' to get 'T_0' or 'T_1'
|
||||
#define __TERN(T,V...) ___TERN(_CAT(_NO,T),V) // Prepend '_NO' to get '_NOT_0' or '_NOT_1'
|
||||
#define ___TERN(P,V...) THIRD(P,V) // If first argument has a comma, A. Else B.
|
||||
|
||||
|
||||
// Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments
|
||||
#define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT
|
||||
#define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
|
||||
|
||||
//
|
||||
// Primitives supporting precompiler REPEAT
|
||||
//
|
||||
#define FIRST(a,...) a
|
||||
#define SECOND(a,b,...) b
|
||||
#define THIRD(a,b,c,...) c
|
||||
|
||||
#define IS_PROBE(V...) SECOND(V, 0) // Get the second item passed, or 0
|
||||
#define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'.
|
||||
|
||||
#endif //MACROS_H
|
@ -8,6 +8,7 @@
|
||||
#include "lcd.h"
|
||||
#include "Configuration.h"
|
||||
#include "Marlin.h"
|
||||
#include "cmdqueue.h"
|
||||
#include "ultralcd.h"
|
||||
#include "language.h"
|
||||
#include "static_assert.h"
|
||||
@ -48,6 +49,7 @@ void menu_goto(menu_func_t menu, const uint32_t encoder, const bool feedback, bo
|
||||
{
|
||||
menu_menu = menu;
|
||||
lcd_encoder = encoder;
|
||||
menu_top = 0; //reset menu view. Needed if menu_back() is called from deep inside a menu, such as Support
|
||||
asm("sei");
|
||||
if (reset_menu_state)
|
||||
{
|
||||
@ -250,8 +252,7 @@ static void menu_draw_item_puts_P(char type_char, const char* str, char num)
|
||||
lcd_set_cursor(0, menu_row);
|
||||
lcd_printf_P(PSTR("%c%-.16S "), menu_selection_mark(), str);
|
||||
lcd_putc(num);
|
||||
lcd_set_cursor(19, menu_row);
|
||||
lcd_putc(type_char);
|
||||
lcd_putc_at(19, menu_row, type_char);
|
||||
}
|
||||
|
||||
/*
|
||||
@ -310,7 +311,7 @@ uint8_t menu_item_submenu_E(const Sheet &sheet, menu_func_t submenu)
|
||||
return 0;
|
||||
}
|
||||
|
||||
uint8_t menu_item_function_E(const Sheet &sheet, menu_func_t func)
|
||||
uint8_t __attribute__((noinline)) menu_item_function_E(const Sheet &sheet, menu_func_t func)
|
||||
{
|
||||
if (menu_item == menu_line)
|
||||
{
|
||||
@ -344,6 +345,10 @@ uint8_t menu_item_back_P(const char* str)
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool __attribute__((noinline)) menu_item_leave(){
|
||||
return ((menu_item == menu_line) && menu_clicked && (lcd_encoder == menu_item)) || menu_leaving;
|
||||
}
|
||||
|
||||
uint8_t menu_item_function_P(const char* str, menu_func_t func)
|
||||
{
|
||||
if (menu_item == menu_line)
|
||||
|
@ -112,7 +112,8 @@ extern uint8_t menu_item_function_E(const Sheet &sheet, menu_func_t func);
|
||||
extern uint8_t menu_item_back_P(const char* str);
|
||||
|
||||
// leaving menu - this condition must be immediately before MENU_ITEM_BACK_P
|
||||
#define ON_MENU_LEAVE(func) do { if (((menu_item == menu_line) && menu_clicked && (lcd_encoder == menu_item)) || menu_leaving){ func } } while (0)
|
||||
#define ON_MENU_LEAVE(func) do { if (menu_item_leave()){ func } } while (0)
|
||||
extern bool menu_item_leave();
|
||||
|
||||
#define MENU_ITEM_FUNCTION_P(str, func) do { if (menu_item_function_P(str, func)) return; } while (0)
|
||||
extern uint8_t menu_item_function_P(const char* str, menu_func_t func);
|
||||
|
@ -12,6 +12,8 @@
|
||||
#include "tmc2130.h"
|
||||
#endif //TMC2130
|
||||
|
||||
#define DBG(args...) printf_P(args)
|
||||
|
||||
uint8_t world2machine_correction_mode;
|
||||
float world2machine_rotation_and_skew[2][2];
|
||||
float world2machine_rotation_and_skew_inv[2][2];
|
||||
@ -369,7 +371,9 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
|
||||
BedSkewOffsetDetectionResultType result = BED_SKEW_OFFSET_DETECTION_PERFECT;
|
||||
{
|
||||
angleDiff = fabs(a2 - a1);
|
||||
eeprom_update_float((float*)(EEPROM_XYZ_CAL_SKEW), angleDiff); //storing xyz cal. skew to be able to show in support menu later
|
||||
/// XY skew and Y-bed skew
|
||||
DBG(_n("Measured skews: %f %f\n"), degrees(a2 - a1), degrees(a2));
|
||||
eeprom_update_float((float *)(EEPROM_XYZ_CAL_SKEW), angleDiff); //storing xyz cal. skew to be able to show in support menu later
|
||||
if (angleDiff > bed_skew_angle_mild)
|
||||
result = (angleDiff > bed_skew_angle_extreme) ?
|
||||
BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME :
|
||||
@ -1380,7 +1384,7 @@ inline bool find_bed_induction_sensor_point_xy(int verbosity_level)
|
||||
|
||||
// go_xyz(current_position[X_AXIS], current_position[Y_AXIS], MESH_HOME_Z_SEARCH, homing_feedrate[Z_AXIS]/60);
|
||||
go_xyz(x0, y0, current_position[Z_AXIS], feedrate);
|
||||
// Continously lower the Z axis.
|
||||
// Continuously lower the Z axis.
|
||||
endstops_hit_on_purpose();
|
||||
enable_z_endstop(true);
|
||||
while (current_position[Z_AXIS] > -10.f) {
|
||||
@ -2271,7 +2275,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
/*}
|
||||
else {
|
||||
// if first iteration failed, count corrected point coordinates as initial
|
||||
// Use the coorrected coordinate, which is a result of find_bed_offset_and_skew().
|
||||
// Use the corrected coordinate, which is a result of find_bed_offset_and_skew().
|
||||
|
||||
current_position[X_AXIS] = vec_x[0] * pgm_read_float(bed_ref_points_4 + k * 2) + vec_y[0] * pgm_read_float(bed_ref_points_4 + k * 2 + 1) + cntr[0];
|
||||
current_position[Y_AXIS] = vec_x[1] * pgm_read_float(bed_ref_points_4 + k * 2) + vec_y[1] * pgm_read_float(bed_ref_points_4 + k * 2 + 1) + cntr[1];
|
||||
@ -2375,8 +2379,9 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
delay_keep_alive(3000);
|
||||
}
|
||||
#endif // SUPPORT_VERBOSITY
|
||||
}
|
||||
delay_keep_alive(0); //manage_heater, reset watchdog, manage inactivity
|
||||
}
|
||||
DBG(_n("All 4 calibration points found.\n"));
|
||||
delay_keep_alive(0); //manage_heater, reset watchdog, manage inactivity
|
||||
|
||||
#ifdef SUPPORT_VERBOSITY
|
||||
if (verbosity_level >= 20) {
|
||||
@ -2386,7 +2391,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
// Don't let the manage_inactivity() function remove power from the motors.
|
||||
refresh_cmd_timeout();
|
||||
// Go to the measurement point.
|
||||
// Use the coorrected coordinate, which is a result of find_bed_offset_and_skew().
|
||||
// Use the corrected coordinate, which is a result of find_bed_offset_and_skew().
|
||||
current_position[X_AXIS] = pts[mesh_point * 2];
|
||||
current_position[Y_AXIS] = pts[mesh_point * 2 + 1];
|
||||
go_to_current(homing_feedrate[X_AXIS] / 60);
|
||||
@ -2406,6 +2411,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
delay_keep_alive(0); //manage_heater, reset watchdog, manage inactivity
|
||||
|
||||
if (result >= 0) {
|
||||
DBG(_n("Calibration success.\n"));
|
||||
world2machine_update(vec_x, vec_y, cntr);
|
||||
#if 1
|
||||
// Fearlessly store the calibration values into the eeprom.
|
||||
@ -2450,7 +2456,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
// Don't let the manage_inactivity() function remove power from the motors.
|
||||
refresh_cmd_timeout();
|
||||
// Go to the measurement point.
|
||||
// Use the coorrected coordinate, which is a result of find_bed_offset_and_skew().
|
||||
// Use the corrected coordinate, which is a result of find_bed_offset_and_skew().
|
||||
uint8_t ix = mesh_point % MESH_MEAS_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1
|
||||
uint8_t iy = mesh_point / MESH_MEAS_NUM_X_POINTS;
|
||||
if (iy & 1) ix = (MESH_MEAS_NUM_X_POINTS - 1) - ix;
|
||||
@ -2462,9 +2468,12 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
|
||||
}
|
||||
#endif // SUPPORT_VERBOSITY
|
||||
return result;
|
||||
}
|
||||
if (result == BED_SKEW_OFFSET_DETECTION_FITTING_FAILED && too_far_mask == 2) return result; //if fitting failed and front center point is out of reach, terminate calibration and inform user
|
||||
iteration++;
|
||||
}
|
||||
if (result == BED_SKEW_OFFSET_DETECTION_FITTING_FAILED && too_far_mask == 2){
|
||||
DBG(_n("Fitting failed => calibration failed.\n"));
|
||||
return result; //if fitting failed and front center point is out of reach, terminate calibration and inform user
|
||||
}
|
||||
iteration++;
|
||||
}
|
||||
return result;
|
||||
}
|
||||
|
@ -16,17 +16,24 @@ const char MSG_BED_DONE[] PROGMEM_I1 = ISTR("Bed done"); ////
|
||||
const char MSG_BED_HEATING[] PROGMEM_I1 = ISTR("Bed Heating"); ////
|
||||
const char MSG_BED_LEVELING_FAILED_POINT_LOW[] PROGMEM_I1 = ISTR("Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."); ////c=20 r=5
|
||||
const char MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED[] PROGMEM_I1 = ISTR("XYZ calibration failed. Please consult the manual."); ////c=20 r=8
|
||||
const char MSG_BELT_STATUS[] PROGMEM_I1 = ISTR("Belt Status");////c=18
|
||||
const char MSG_CALIBRATE_Z_AUTO[] PROGMEM_I1 = ISTR("Calibrating Z"); ////c=20 r=2
|
||||
const char MSG_CARD_MENU[] PROGMEM_I1 = ISTR("Print from SD"); ////
|
||||
const char MSG_CHECKING_X[] PROGMEM_I1 = ISTR("Checking X axis"); ////c=20
|
||||
const char MSG_CHECKING_Y[] PROGMEM_I1 = ISTR("Checking Y axis"); ////c=20
|
||||
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[] PROGMEM_I1 = ISTR("Crash"); ////c=7
|
||||
const char MSG_CRASH_DETECTED[] PROGMEM_I1 = ISTR("Crash detected."); ////c=20 r=1
|
||||
const char MSG_CRASHDETECT[] PROGMEM_I1 = ISTR("Crash det."); ////c=13
|
||||
const char MSG_ERROR[] PROGMEM_I1 = ISTR("ERROR:"); ////
|
||||
const char MSG_EXTRUDER[] PROGMEM_I1 = ISTR("Extruder"); ////c=17 r=1
|
||||
const char MSG_EXTRUDER[] PROGMEM_I1 = ISTR("Extruder"); ////c=17
|
||||
const char MSG_FANS_CHECK[] PROGMEM_I1 = ISTR("Fans check"); ////c=13
|
||||
const char MSG_FIL_RUNOUTS[] PROGMEM_I1 = ISTR("Fil. runouts"); ////c=14
|
||||
const char MSG_FILAMENT[] PROGMEM_I1 = ISTR("Filament"); ////c=17 r=1
|
||||
const char MSG_FAN_SPEED[] PROGMEM_I1 = ISTR("Fan speed"); ////c=14
|
||||
const char MSG_FILAMENT_CLEAN[] PROGMEM_I1 = ISTR("Filament extruding & with correct color?"); ////c=20 r=2
|
||||
const char MSG_FILAMENT_LOADED[] PROGMEM_I1 = ISTR("Is filament loaded?"); ////c=20 r=2
|
||||
const char MSG_FILAMENT_LOADING_T0[] PROGMEM_I1 = ISTR("Insert filament into extruder 1. Click when done."); ////c=20 r=4
|
||||
const char MSG_FILAMENT_LOADING_T1[] PROGMEM_I1 = ISTR("Insert filament into extruder 2. Click when done."); ////c=20 r=4
|
||||
const char MSG_FILAMENT_LOADING_T2[] PROGMEM_I1 = ISTR("Insert filament into extruder 3. Click when done."); ////c=20 r=4
|
||||
@ -44,6 +51,8 @@ const char MSG_HEATING_COMPLETE[] PROGMEM_I1 = ISTR("Heating done."); ////c=20
|
||||
const char MSG_HOMEYZ[] PROGMEM_I1 = ISTR("Calibrate Z"); ////
|
||||
const char MSG_CHOOSE_EXTRUDER[] PROGMEM_I1 = ISTR("Choose extruder:"); ////c=20 r=1
|
||||
const char MSG_CHOOSE_FILAMENT[] PROGMEM_I1 = ISTR("Choose filament:"); ////c=20 r=1
|
||||
const char MSG_LAST_PRINT[] PROGMEM_I1 = ISTR("Last print"); ////c=18
|
||||
const char MSG_LAST_PRINT_FAILURES[] PROGMEM_I1 = ISTR("Last print failures"); ////c=20
|
||||
const char MSG_LOAD_FILAMENT[] PROGMEM_I1 = ISTR("Load filament"); //// Number 1 to 5 is added behind text e.g. "Load filament 1" c=16
|
||||
const char MSG_LOADING_FILAMENT[] PROGMEM_I1 = ISTR("Loading filament"); ////c=20
|
||||
const char MSG_EJECT_FILAMENT[] PROGMEM_I1 = ISTR("Eject filament"); //// Number 1 to 5 is added behind text e.g. "Eject filament 1" c=16
|
||||
@ -52,22 +61,28 @@ const char MSG_M117_V2_CALIBRATION[] PROGMEM_I1 = ISTR("M117 First layer cal.");
|
||||
const char MSG_MAIN[] PROGMEM_I1 = ISTR("Main"); ////
|
||||
const char MSG_BACK[] PROGMEM_I1 = ISTR("Back"); ////
|
||||
const char MSG_SHEET[] PROGMEM_I1 = ISTR("Sheet"); ////c=10
|
||||
const char MSG_STEEL_SHEETS[] PROGMEM_I1 = ISTR("Steel sheets"); ////c=18
|
||||
const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1[] PROGMEM_I1 = ISTR("Measuring reference height of calibration point"); ////c=60
|
||||
const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2[] PROGMEM_I1 = ISTR(" of 9"); ////c=14
|
||||
const char MSG_MENU_CALIBRATION[] PROGMEM_I1 = ISTR("Calibration"); ////
|
||||
const char MSG_MMU_FAILS[] PROGMEM_I1 = ISTR("MMU fails"); ////c=14
|
||||
const char MSG_MMU_LOAD_FAILS[] PROGMEM_I1 = ISTR("MMU load fails"); ////c=14
|
||||
const char MSG_NO[] PROGMEM_I1 = ISTR("No"); ////
|
||||
const char MSG_NOZZLE[] PROGMEM_I1 = ISTR("Nozzle"); ////
|
||||
const char MSG_PAPER[] PROGMEM_I1 = ISTR("Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."); ////c=20 r=10
|
||||
const char MSG_PLACE_STEEL_SHEET[] PROGMEM_I1 = ISTR("Please place steel sheet on heatbed."); ////c=20 r=4
|
||||
const char MSG_PLEASE_WAIT[] PROGMEM_I1 = ISTR("Please wait"); ////c=20
|
||||
const char MSG_POWER_FAILURES[] PROGMEM_I1 = ISTR("Power failures"); ////c=14
|
||||
const char MSG_PREHEAT_NOZZLE[] PROGMEM_I1 = ISTR("Preheat the nozzle!"); ////c=20
|
||||
const char MSG_PRESS_TO_UNLOAD[] PROGMEM_I1 = ISTR("Please press the knob to unload filament"); ////c=20 r=4
|
||||
const char MSG_PRINT_ABORTED[] PROGMEM_I1 = ISTR("Print aborted"); ////c=20
|
||||
const char MSG_PULL_OUT_FILAMENT[] PROGMEM_I1 = ISTR("Please pull out filament immediately"); ////c=20 r=4
|
||||
const char MSG_RECOVER_PRINT[] PROGMEM_I1 = ISTR("Blackout occurred. Recover print?"); ////c=20 r=2
|
||||
const char MSG_REFRESH[] PROGMEM_I1 = ISTR("\xF8" "Refresh"); ////
|
||||
const char MSG_RESUMING_PRINT[] PROGMEM_I1 = ISTR("Resuming print"); ////
|
||||
const char MSG_REMOVE_STEEL_SHEET[] PROGMEM_I1 = ISTR("Please remove steel sheet from heatbed."); ////c=20 r=4
|
||||
const char MSG_RESET[] PROGMEM_I1 = ISTR("Reset"); ////c=14
|
||||
const char MSG_RESUME_PRINT[] PROGMEM_I1 = ISTR("Resume print"); ////c=18
|
||||
const char MSG_RESUMING_PRINT[] PROGMEM_I1 = ISTR("Resuming print"); ////
|
||||
const char MSG_SELFTEST_COOLING_FAN[] PROGMEM_I1 = ISTR("Front print fan?"); ////c=20
|
||||
const char MSG_SELFTEST_EXTRUDER_FAN[] PROGMEM_I1 = ISTR("Left hotend fan?"); ////c=20
|
||||
const char MSG_SELFTEST_FAILED[] PROGMEM_I1 = ISTR("Selftest failed "); ////c=20
|
||||
@ -80,7 +95,9 @@ const char MSG_SELFTEST_MOTOR[] PROGMEM_I1 = ISTR("Motor"); ////
|
||||
const char MSG_SELFTEST_FILAMENT_SENSOR[] PROGMEM_I1 = ISTR("Filament sensor"); ////c=17
|
||||
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_TOTAL[] PROGMEM_I1 = ISTR("Total"); ////c=6
|
||||
const char MSG_TOTAL_FAILURES[] PROGMEM_I1 = ISTR("Total failures"); ////c=20
|
||||
const char MSG_HW_SETUP[] PROGMEM_I1 = ISTR("HW Setup"); ////c=18
|
||||
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"); ////
|
||||
@ -113,6 +130,8 @@ 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_GCODE_DIFF_PRINTER_CONTINUE[] PROGMEM_I1 = ISTR("G-code sliced for a different printer type. Continue?"); ////c=20 r=5
|
||||
const char MSG_GCODE_DIFF_PRINTER_CANCELLED[] PROGMEM_I1 =ISTR("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."); ////c=20 r=6
|
||||
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"); ////
|
||||
@ -126,6 +145,7 @@ 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_MESH_BED_LEVELING[] PROGMEM_I1 = ISTR("Mesh Bed Leveling"); ////c=18
|
||||
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"); ////c=10
|
||||
@ -176,4 +196,4 @@ const char MSG_FANCHECK_PRINT[] PROGMEM_N1 = "Err: PRINT FAN ERROR"; ////c=20
|
||||
const char MSG_M112_KILL[] PROGMEM_N1 = "M112 called. Emergency Stop."; ////c=20
|
||||
const char MSG_ADVANCE_K[] PROGMEM_N1 = "Advance K:"; ////c=13
|
||||
const char MSG_POWERPANIC_DETECTED[] PROGMEM_N1 = "POWER PANIC DETECTED"; ////c=20
|
||||
|
||||
const char MSG_LCD_STATUS_CHANGED[] PROGMEM_N1 = "LCD status changed";
|
||||
|
@ -17,17 +17,24 @@ extern const char MSG_BED_DONE[];
|
||||
extern const char MSG_BED_HEATING[];
|
||||
extern const char MSG_BED_LEVELING_FAILED_POINT_LOW[];
|
||||
extern const char MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED[];
|
||||
extern const char MSG_BELT_STATUS[];
|
||||
extern const char MSG_CALIBRATE_Z_AUTO[];
|
||||
extern const char MSG_CARD_MENU[];
|
||||
extern const char MSG_CHECKING_X[];
|
||||
extern const char MSG_CHECKING_Y[];
|
||||
extern const char MSG_CONFIRM_NOZZLE_CLEAN[];
|
||||
extern const char MSG_COOLDOWN[];
|
||||
extern const char MSG_CRASH[];
|
||||
extern const char MSG_CRASH_DETECTED[];
|
||||
extern const char MSG_CRASHDETECT[];
|
||||
extern const char MSG_ERROR[];
|
||||
extern const char MSG_EXTRUDER[];
|
||||
extern const char MSG_FANS_CHECK[];
|
||||
extern const char MSG_FIL_RUNOUTS[];
|
||||
extern const char MSG_FILAMENT[];
|
||||
extern const char MSG_FAN_SPEED[];
|
||||
extern const char MSG_FILAMENT_CLEAN[];
|
||||
extern const char MSG_FILAMENT_LOADED[];
|
||||
extern const char MSG_FILAMENT_LOADING_T0[];
|
||||
extern const char MSG_FILAMENT_LOADING_T1[];
|
||||
extern const char MSG_FILAMENT_LOADING_T2[];
|
||||
@ -45,20 +52,26 @@ extern const char MSG_HEATING_COMPLETE[];
|
||||
extern const char MSG_HOMEYZ[];
|
||||
extern const char MSG_CHOOSE_EXTRUDER[];
|
||||
extern const char MSG_CHOOSE_FILAMENT[];
|
||||
extern const char MSG_LAST_PRINT[];
|
||||
extern const char MSG_LAST_PRINT_FAILURES[];
|
||||
extern const char MSG_LOAD_FILAMENT[];
|
||||
extern const char MSG_LOADING_FILAMENT[];
|
||||
extern const char MSG_M117_V2_CALIBRATION[];
|
||||
extern const char MSG_MAIN[];
|
||||
extern const char MSG_BACK[];
|
||||
extern const char MSG_SHEET[];
|
||||
extern const char MSG_STEEL_SHEETS[];
|
||||
extern const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1[];
|
||||
extern const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2[];
|
||||
extern const char MSG_MENU_CALIBRATION[];
|
||||
extern const char MSG_MMU_FAILS[];
|
||||
extern const char MSG_MMU_LOAD_FAILS[];
|
||||
extern const char MSG_NO[];
|
||||
extern const char MSG_NOZZLE[];
|
||||
extern const char MSG_PAPER[];
|
||||
extern const char MSG_PLACE_STEEL_SHEET[];
|
||||
extern const char MSG_PLEASE_WAIT[];
|
||||
extern const char MSG_POWER_FAILURES[];
|
||||
extern const char MSG_PREHEAT_NOZZLE[];
|
||||
extern const char MSG_PRESS_TO_UNLOAD[];
|
||||
extern const char MSG_PRINT_ABORTED[];
|
||||
@ -66,6 +79,8 @@ extern const char MSG_PULL_OUT_FILAMENT[];
|
||||
extern const char MSG_RECOVER_PRINT[];
|
||||
extern const char MSG_REFRESH[];
|
||||
extern const char MSG_REMOVE_STEEL_SHEET[];
|
||||
extern const char MSG_RESET[];
|
||||
extern const char MSG_RESUME_PRINT[];
|
||||
extern const char MSG_RESUMING_PRINT[];
|
||||
extern const char MSG_SD_WORKDIR_FAIL[];
|
||||
extern const char MSG_SELFTEST_COOLING_FAN[];
|
||||
@ -80,6 +95,8 @@ extern const char MSG_SELFTEST_MOTOR[];
|
||||
extern const char MSG_SELFTEST_FILAMENT_SENSOR[];
|
||||
extern const char MSG_SELFTEST_WIRINGERROR[];
|
||||
extern const char MSG_SETTINGS[];
|
||||
extern const char MSG_TOTAL[];
|
||||
extern const char MSG_TOTAL_FAILURES[];
|
||||
extern const char MSG_HW_SETUP[];
|
||||
extern const char MSG_MODE[];
|
||||
extern const char MSG_HIGH_POWER[];
|
||||
@ -113,6 +130,8 @@ extern const char MSG_STRICT[];
|
||||
extern const char MSG_MODEL[];
|
||||
extern const char MSG_FIRMWARE[];
|
||||
extern const char MSG_GCODE[];
|
||||
extern const char MSG_GCODE_DIFF_PRINTER_CONTINUE[];
|
||||
extern const char MSG_GCODE_DIFF_PRINTER_CANCELLED[];
|
||||
extern const char MSG_NOZZLE_DIAMETER[];
|
||||
extern const char MSG_MMU_MODE[];
|
||||
extern const char MSG_SD_CARD[];
|
||||
@ -126,6 +145,7 @@ 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_MESH_BED_LEVELING[];
|
||||
extern const char MSG_Z_PROBE_NR[];
|
||||
extern const char MSG_MAGNETS_COMP[];
|
||||
extern const char MSG_FS_ACTION[];
|
||||
@ -176,6 +196,7 @@ extern const char MSG_FANCHECK_PRINT[];
|
||||
extern const char MSG_M112_KILL[];
|
||||
extern const char MSG_ADVANCE_K[];
|
||||
extern const char MSG_POWERPANIC_DETECTED[];
|
||||
extern const char MSG_LCD_STATUS_CHANGED[];
|
||||
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
|
@ -9,12 +9,14 @@
|
||||
#include "Configuration_prusa.h"
|
||||
#include "fsensor.h"
|
||||
#include "cardreader.h"
|
||||
#include "cmdqueue.h"
|
||||
#include "ultralcd.h"
|
||||
#include "sound.h"
|
||||
#include "printers.h"
|
||||
#include <avr/pgmspace.h>
|
||||
#include "io_atmega2560.h"
|
||||
#include "AutoDeplete.h"
|
||||
#include "fastio.h"
|
||||
#include "pins.h"
|
||||
//-//
|
||||
#include "util.h"
|
||||
|
||||
@ -28,9 +30,6 @@
|
||||
#define MMU_P0_TIMEOUT 3000ul //timeout for P0 command: 3seconds
|
||||
#define MMU_MAX_RESEND_ATTEMPTS 2
|
||||
|
||||
#ifdef MMU_HWRESET
|
||||
#define MMU_RST_PIN 76
|
||||
#endif //MMU_HWRESET
|
||||
|
||||
namespace
|
||||
{
|
||||
@ -156,8 +155,8 @@ void mmu_init(void)
|
||||
_delay_ms(10); //wait 10ms for sure
|
||||
mmu_reset(); //reset mmu (HW or SW), do not wait for response
|
||||
mmu_state = S::Init;
|
||||
PIN_INP(IR_SENSOR_PIN); //input mode
|
||||
PIN_SET(IR_SENSOR_PIN); //pullup
|
||||
SET_INPUT(IR_SENSOR_PIN); //input mode
|
||||
WRITE(IR_SENSOR_PIN, 1); //pullup
|
||||
}
|
||||
|
||||
//if IR_SENSOR defined, always returns true
|
||||
@ -170,7 +169,7 @@ bool check_for_ir_sensor()
|
||||
|
||||
bool detected = false;
|
||||
//if IR_SENSOR_PIN input is low and pat9125sensor is not present we detected idler sensor
|
||||
if ((PIN_GET(IR_SENSOR_PIN) == 0)
|
||||
if ((READ(IR_SENSOR_PIN) == 0)
|
||||
#ifdef PAT9125
|
||||
&& fsensor_not_responding
|
||||
#endif //PAT9125
|
||||
@ -363,7 +362,7 @@ void mmu_loop(void)
|
||||
case S::GetFinda: //response to command P0
|
||||
if (mmu_idl_sens)
|
||||
{
|
||||
if (PIN_GET(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
|
||||
if (READ(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
|
||||
{
|
||||
#ifdef MMU_DEBUG
|
||||
printf_P(PSTR("MMU <= 'A'\n"));
|
||||
@ -406,7 +405,7 @@ void mmu_loop(void)
|
||||
case S::WaitCmd: //response to mmu commands
|
||||
if (mmu_idl_sens)
|
||||
{
|
||||
if (PIN_GET(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
|
||||
if (READ(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
|
||||
{
|
||||
DEBUG_PRINTF_P(PSTR("MMU <= 'A'\n"));
|
||||
mmu_puts_P(PSTR("A\n")); //send 'abort' request
|
||||
@ -568,11 +567,11 @@ bool can_extrude()
|
||||
static void get_response_print_info(uint8_t move) {
|
||||
printf_P(PSTR("mmu_get_response - begin move: "), move);
|
||||
switch (move) {
|
||||
case MMU_LOAD_MOVE: printf_P(PSTR("load\n")); break;
|
||||
case MMU_UNLOAD_MOVE: printf_P(PSTR("unload\n")); break;
|
||||
case MMU_TCODE_MOVE: printf_P(PSTR("T-code\n")); break;
|
||||
case MMU_NO_MOVE: printf_P(PSTR("no move\n")); break;
|
||||
default: printf_P(PSTR("error: unknown move\n")); break;
|
||||
case MMU_LOAD_MOVE: puts_P(PSTR("load")); break;
|
||||
case MMU_UNLOAD_MOVE: puts_P(PSTR("unload")); break;
|
||||
case MMU_TCODE_MOVE: puts_P(PSTR("T-code")); break;
|
||||
case MMU_NO_MOVE: puts_P(PSTR("no move")); break;
|
||||
default: puts_P(PSTR("error: unknown move")); break;
|
||||
}
|
||||
}
|
||||
|
||||
@ -596,14 +595,14 @@ bool mmu_get_response(uint8_t move)
|
||||
mmu_loading_flag = true;
|
||||
if (can_extrude()) mmu_load_step();
|
||||
//don't rely on "ok" signal from mmu unit; if filament detected by idler sensor during loading stop loading movements to prevent infinite loading
|
||||
if (PIN_GET(IR_SENSOR_PIN) == 0) move = MMU_NO_MOVE;
|
||||
if (READ(IR_SENSOR_PIN) == 0) move = MMU_NO_MOVE;
|
||||
break;
|
||||
case MMU_UNLOAD_MOVE:
|
||||
if (PIN_GET(IR_SENSOR_PIN) == 0) //filament is still detected by idler sensor, printer helps with unlading
|
||||
if (READ(IR_SENSOR_PIN) == 0) //filament is still detected by idler sensor, printer helps with unlading
|
||||
{
|
||||
if (can_extrude())
|
||||
{
|
||||
printf_P(PSTR("Unload 1\n"));
|
||||
puts_P(PSTR("Unload 1"));
|
||||
current_position[E_AXIS] = current_position[E_AXIS] - MMU_LOAD_FEEDRATE * MMU_LOAD_TIME_MS*0.001;
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
|
||||
st_synchronize();
|
||||
@ -611,17 +610,17 @@ bool mmu_get_response(uint8_t move)
|
||||
}
|
||||
else //filament was unloaded from idler, no additional movements needed
|
||||
{
|
||||
printf_P(PSTR("Unloading finished 1\n"));
|
||||
puts_P(PSTR("Unloading finished 1"));
|
||||
disable_e0(); //turn off E-stepper to prevent overheating and alow filament pull-out if necessary
|
||||
move = MMU_NO_MOVE;
|
||||
}
|
||||
break;
|
||||
case MMU_TCODE_MOVE: //first do unload and then continue with infinite loading movements
|
||||
if (PIN_GET(IR_SENSOR_PIN) == 0) //filament detected by idler sensor, we must unload first
|
||||
if (READ(IR_SENSOR_PIN) == 0) //filament detected by idler sensor, we must unload first
|
||||
{
|
||||
if (can_extrude())
|
||||
{
|
||||
printf_P(PSTR("Unload 2\n"));
|
||||
puts_P(PSTR("Unload 2"));
|
||||
current_position[E_AXIS] = current_position[E_AXIS] - MMU_LOAD_FEEDRATE * MMU_LOAD_TIME_MS*0.001;
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
|
||||
st_synchronize();
|
||||
@ -629,7 +628,7 @@ bool mmu_get_response(uint8_t move)
|
||||
}
|
||||
else //delay to allow mmu unit to pull out filament from bondtech gears and then start with infinite loading
|
||||
{
|
||||
printf_P(PSTR("Unloading finished 2\n"));
|
||||
puts_P(PSTR("Unloading finished 2"));
|
||||
disable_e0(); //turn off E-stepper to prevent overheating and alow filament pull-out if necessary
|
||||
delay_keep_alive(MMU_LOAD_TIME_MS);
|
||||
move = MMU_LOAD_MOVE;
|
||||
@ -690,7 +689,7 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
|
||||
}
|
||||
st_synchronize();
|
||||
mmu_print_saved = true;
|
||||
printf_P(PSTR("MMU not responding\n"));
|
||||
puts_P(PSTR("MMU not responding"));
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
hotend_temp_bckp = degTargetHotend(active_extruder);
|
||||
if (move_axes) {
|
||||
@ -747,7 +746,7 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
|
||||
}
|
||||
}
|
||||
else if (mmu_print_saved) {
|
||||
printf_P(PSTR("MMU starts responding\n"));
|
||||
puts_P(PSTR("MMU starts responding"));
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
mmu_loading_flag = false;
|
||||
if (turn_off_nozzle)
|
||||
@ -879,8 +878,8 @@ void mmu_M600_load_filament(bool automatic, float nozzle_temp)
|
||||
}
|
||||
lcd_update_enable(false);
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_LOADING_FILAMENT));
|
||||
lcd_print(" ");
|
||||
lcd_puts_at_P(0, 1, _T(MSG_LOADING_FILAMENT));
|
||||
lcd_print(' ');
|
||||
lcd_print(tmp_extruder + 1);
|
||||
snmm_filaments_used |= (1 << tmp_extruder); //for stop print
|
||||
|
||||
@ -992,10 +991,10 @@ void extr_adj(uint8_t extruder) //loading filament for SNMM
|
||||
|
||||
lcd_update_enable(false);
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_LOADING_FILAMENT));
|
||||
lcd_puts_at_P(0, 1, _T(MSG_LOADING_FILAMENT));
|
||||
//if(strlen(_T(MSG_LOADING_FILAMENT))>18) lcd.setCursor(0, 1);
|
||||
//else lcd.print(" ");
|
||||
lcd_print(" ");
|
||||
lcd_print(' ');
|
||||
lcd_print(extruder + 1);
|
||||
|
||||
// get response
|
||||
@ -1035,7 +1034,7 @@ void extr_adj(uint8_t extruder) //loading filament for SNMM
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 0); lcd_puts_P(_T(MSG_LOADING_FILAMENT));
|
||||
if(strlen(_T(MSG_LOADING_FILAMENT))>18) lcd_set_cursor(0, 1);
|
||||
else lcd_print(" ");
|
||||
else lcd_print(' ');
|
||||
lcd_print(mmu_extruder + 1);
|
||||
lcd_set_cursor(0, 2); lcd_puts_P(_T(MSG_PLEASE_WAIT));
|
||||
st_synchronize();
|
||||
@ -1082,9 +1081,9 @@ void mmu_filament_ramming()
|
||||
void extr_unload_view()
|
||||
{
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_UNLOADING_FILAMENT));
|
||||
lcd_print(" ");
|
||||
if (mmu_extruder == MMU_FILAMENT_UNKNOWN) lcd_print(" ");
|
||||
lcd_puts_at_P(0, 1, _T(MSG_UNLOADING_FILAMENT));
|
||||
lcd_print(' ');
|
||||
if (mmu_extruder == MMU_FILAMENT_UNKNOWN) lcd_print(' ');
|
||||
else lcd_print(mmu_extruder + 1);
|
||||
}
|
||||
|
||||
@ -1116,7 +1115,7 @@ void extr_unload()
|
||||
lcd_display_message_fullscreen_P(PSTR(""));
|
||||
max_feedrate[E_AXIS] = 50;
|
||||
lcd_set_cursor(0, 0); lcd_puts_P(_T(MSG_UNLOADING_FILAMENT));
|
||||
lcd_print(" ");
|
||||
lcd_print(' ');
|
||||
lcd_print(mmu_extruder + 1);
|
||||
lcd_set_cursor(0, 2); lcd_puts_P(_T(MSG_PLEASE_WAIT));
|
||||
if (current_position[Z_AXIS] < 15) {
|
||||
@ -1350,9 +1349,8 @@ void lcd_mmu_load_to_nozzle(uint8_t filament_nr)
|
||||
tmp_extruder = filament_nr;
|
||||
lcd_update_enable(false);
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 1);
|
||||
lcd_puts_P(_T(MSG_LOADING_FILAMENT));
|
||||
lcd_print(" ");
|
||||
lcd_puts_at_P(0, 1, _T(MSG_LOADING_FILAMENT));
|
||||
lcd_print(' ');
|
||||
lcd_print(tmp_extruder + 1);
|
||||
mmu_command(MmuCmd::T0 + tmp_extruder);
|
||||
manage_response(true, true, MMU_TCODE_MOVE);
|
||||
@ -1385,8 +1383,8 @@ void mmu_cut_filament(uint8_t filament_nr)
|
||||
{
|
||||
LcdUpdateDisabler disableLcdUpdate;
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 1); lcd_puts_P(_i("Cutting filament")); //// c=18
|
||||
lcd_print(" ");
|
||||
lcd_puts_at_P(0, 1, _i("Cutting filament")); //// c=18
|
||||
lcd_print(' ');
|
||||
lcd_print(filament_nr + 1);
|
||||
mmu_filament_ramming();
|
||||
mmu_command(MmuCmd::K0 + filament_nr);
|
||||
@ -1413,7 +1411,7 @@ bFilamentAction=false; // NOT in "mmu_fil_eject_menu(
|
||||
{
|
||||
LcdUpdateDisabler disableLcdUpdate;
|
||||
lcd_clear();
|
||||
lcd_set_cursor(0, 1); lcd_puts_P(_i("Ejecting filament"));
|
||||
lcd_puts_at_P(0, 1, _i("Ejecting filament"));
|
||||
mmu_filament_ramming();
|
||||
mmu_command(MmuCmd::E0 + filament);
|
||||
manage_response(false, false, MMU_UNLOAD_MOVE);
|
||||
@ -1460,7 +1458,7 @@ static bool can_load()
|
||||
current_position[E_AXIS] -= e_increment;
|
||||
plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
|
||||
st_synchronize();
|
||||
if(0 == PIN_GET(IR_SENSOR_PIN))
|
||||
if(0 == READ(IR_SENSOR_PIN))
|
||||
{
|
||||
++filament_detected_count;
|
||||
DEBUG_PUTCHAR('O');
|
||||
@ -1491,7 +1489,7 @@ static bool load_more()
|
||||
{
|
||||
for (uint8_t i = 0; i < MMU_IDLER_SENSOR_ATTEMPTS_NR; i++)
|
||||
{
|
||||
if (PIN_GET(IR_SENSOR_PIN) == 0) return true;
|
||||
if (READ(IR_SENSOR_PIN) == 0) return true;
|
||||
DEBUG_PRINTF_P(PSTR("Additional load attempt nr. %d\n"), i);
|
||||
mmu_command(MmuCmd::C0);
|
||||
manage_response(true, true, MMU_LOAD_MOVE);
|
||||
|
@ -115,6 +115,8 @@
|
||||
|
||||
#define IR_SENSOR_PIN 62 //idler sensor @PK0 (digital pin 62/A8)
|
||||
|
||||
#define MMU_RST_PIN 76
|
||||
|
||||
// Support for an 8 bit logic analyzer, for example the Saleae.
|
||||
// Channels 0-2 are fast, they could generate 2.667Mhz waveform with a software loop.
|
||||
#define LOGIC_ANALYZER_CH0 X_MIN_PIN // PB6
|
||||
|
@ -129,11 +129,15 @@ void sm4_set_dir_bits(uint8_t dir_bits)
|
||||
void sm4_do_step(uint8_t axes_mask)
|
||||
{
|
||||
#if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3) || (MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
#ifdef TMC2130_DEDGE_STEPPING
|
||||
PINC = (axes_mask & 0x0f); // toggle step signals by mask
|
||||
#else
|
||||
register uint8_t portC = PORTC & 0xf0;
|
||||
PORTC = portC | (axes_mask & 0x0f); //set step signals by mask
|
||||
asm("nop");
|
||||
PORTC = portC; //set step signals to zero
|
||||
asm("nop");
|
||||
#endif
|
||||
#endif //((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3) || (MOTHERBOARD == BOARD_EINSY_1_0a))
|
||||
}
|
||||
|
||||
@ -173,7 +177,7 @@ uint16_t sm4_line_xyze_ui(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de)
|
||||
}
|
||||
if (ce <= de)
|
||||
{
|
||||
sm |= 4;
|
||||
sm |= 8;
|
||||
ce += dd;
|
||||
e++;
|
||||
}
|
||||
@ -191,5 +195,45 @@ uint16_t sm4_line_xyze_ui(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de)
|
||||
return nd;
|
||||
}
|
||||
|
||||
uint16_t sm4_line_xyz_ui(uint16_t dx, uint16_t dy, uint16_t dz){
|
||||
uint16_t dd = (uint16_t)(sqrt((float)(((uint32_t)dx)*dx + ((uint32_t)dy*dy) + ((uint32_t)dz*dz))) + 0.5);
|
||||
uint16_t nd = dd;
|
||||
uint16_t cx = dd;
|
||||
uint16_t cy = dd;
|
||||
uint16_t cz = dd;
|
||||
uint16_t x = 0;
|
||||
uint16_t y = 0;
|
||||
uint16_t z = 0;
|
||||
while (nd){
|
||||
if (sm4_stop_cb && (*sm4_stop_cb)()) break;
|
||||
uint8_t sm = 0; //step mask
|
||||
if (cx <= dx){
|
||||
sm |= 1;
|
||||
cx += dd;
|
||||
x++;
|
||||
}
|
||||
if (cy <= dy){
|
||||
sm |= 2;
|
||||
cy += dd;
|
||||
y++;
|
||||
}
|
||||
if (cz <= dz){
|
||||
sm |= 4;
|
||||
cz += dd;
|
||||
z++;
|
||||
}
|
||||
cx -= dx;
|
||||
cy -= dy;
|
||||
cz -= dz;
|
||||
sm4_do_step(sm);
|
||||
uint16_t delay = SM4_DEFDELAY;
|
||||
if (sm4_calc_delay_cb) delay = (*sm4_calc_delay_cb)(nd, dd);
|
||||
if (delay) delayMicroseconds(delay);
|
||||
nd--;
|
||||
}
|
||||
if (sm4_update_pos_cb)
|
||||
(*sm4_update_pos_cb)(x, y, z, 0);
|
||||
return nd;
|
||||
}
|
||||
|
||||
#endif //NEW_XYZCAL
|
||||
|
@ -48,6 +48,7 @@ extern void sm4_do_step(uint8_t axes_mask);
|
||||
|
||||
// xyze linear-interpolated relative move, returns remaining diagonal steps (>0 means stoped)
|
||||
extern uint16_t sm4_line_xyze_ui(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de);
|
||||
extern uint16_t sm4_line_xyz_ui(uint16_t dx, uint16_t dy, uint16_t dz);
|
||||
|
||||
|
||||
#if defined(__cplusplus)
|
||||
|
@ -48,6 +48,62 @@ int fsensor_counter; //counter for e-steps
|
||||
uint16_t SP_min = 0x21FF;
|
||||
#endif //DEBUG_STACK_MONITOR
|
||||
|
||||
|
||||
/*
|
||||
* Stepping macros
|
||||
*/
|
||||
#define _STEP_PIN_X_AXIS X_STEP_PIN
|
||||
#define _STEP_PIN_Y_AXIS Y_STEP_PIN
|
||||
#define _STEP_PIN_Z_AXIS Z_STEP_PIN
|
||||
#define _STEP_PIN_E_AXIS E0_STEP_PIN
|
||||
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
#define _STEP_PIN_X_DUP_AXIS DEBUG_XSTEP_DUP_PIN
|
||||
#endif
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
#define _STEP_PIN_Y_DUP_AXIS DEBUG_YSTEP_DUP_PIN
|
||||
#endif
|
||||
#ifdef Y_DUAL_STEPPER_DRIVERS
|
||||
#error Y_DUAL_STEPPER_DRIVERS not fully implemented
|
||||
#define _STEP_PIN_Y2_AXIS Y2_STEP_PIN
|
||||
#endif
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
#error Z_DUAL_STEPPER_DRIVERS not fully implemented
|
||||
#define _STEP_PIN_Z2_AXIS Z2_STEP_PIN
|
||||
#endif
|
||||
|
||||
#ifdef TMC2130
|
||||
#define STEPPER_MINIMUM_PULSE TMC2130_MINIMUM_PULSE
|
||||
#define STEPPER_SET_DIR_DELAY TMC2130_SET_DIR_DELAY
|
||||
#define STEPPER_MINIMUM_DELAY TMC2130_MINIMUM_DELAY
|
||||
#else
|
||||
#define STEPPER_MINIMUM_PULSE 2
|
||||
#define STEPPER_SET_DIR_DELAY 100
|
||||
#define STEPPER_MINIMUM_DELAY delayMicroseconds(STEPPER_MINIMUM_PULSE)
|
||||
#endif
|
||||
|
||||
#ifdef TMC2130_DEDGE_STEPPING
|
||||
static_assert(TMC2130_MINIMUM_DELAY 1, // this will fail to compile when non-empty
|
||||
"DEDGE implies/requires an empty TMC2130_MINIMUM_DELAY");
|
||||
#define STEP_NC_HI(axis) TOGGLE(_STEP_PIN_##axis)
|
||||
#define STEP_NC_LO(axis) //NOP
|
||||
#else
|
||||
|
||||
#define _STEP_HI_X_AXIS !INVERT_X_STEP_PIN
|
||||
#define _STEP_LO_X_AXIS INVERT_X_STEP_PIN
|
||||
#define _STEP_HI_Y_AXIS !INVERT_Y_STEP_PIN
|
||||
#define _STEP_LO_Y_AXIS INVERT_Y_STEP_PIN
|
||||
#define _STEP_HI_Z_AXIS !INVERT_Z_STEP_PIN
|
||||
#define _STEP_LO_Z_AXIS INVERT_Z_STEP_PIN
|
||||
#define _STEP_HI_E_AXIS !INVERT_E_STEP_PIN
|
||||
#define _STEP_LO_E_AXIS INVERT_E_STEP_PIN
|
||||
|
||||
#define STEP_NC_HI(axis) WRITE_NC(_STEP_PIN_##axis, _STEP_HI_##axis)
|
||||
#define STEP_NC_LO(axis) WRITE_NC(_STEP_PIN_##axis, _STEP_LO_##axis)
|
||||
|
||||
#endif //TMC2130_DEDGE_STEPPING
|
||||
|
||||
|
||||
//===========================================================================
|
||||
//=============================public variables ============================
|
||||
//===========================================================================
|
||||
@ -296,13 +352,13 @@ FORCE_INLINE void stepper_next_block()
|
||||
WRITE_NC(X_DIR_PIN, INVERT_X_DIR);
|
||||
else
|
||||
WRITE_NC(X_DIR_PIN, !INVERT_X_DIR);
|
||||
_delay_us(100);
|
||||
delayMicroseconds(STEPPER_SET_DIR_DELAY);
|
||||
for (uint8_t i = 0; i < st_backlash_x; i++)
|
||||
{
|
||||
WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
||||
_delay_us(100);
|
||||
WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
|
||||
_delay_us(900);
|
||||
STEP_NC_HI(X_AXIS);
|
||||
STEPPER_MINIMUM_DELAY;
|
||||
STEP_NC_LO(X_AXIS);
|
||||
_delay_us(900); // hard-coded jerk! *bad*
|
||||
}
|
||||
}
|
||||
last_dir_bits &= ~1;
|
||||
@ -319,13 +375,13 @@ FORCE_INLINE void stepper_next_block()
|
||||
WRITE_NC(Y_DIR_PIN, INVERT_Y_DIR);
|
||||
else
|
||||
WRITE_NC(Y_DIR_PIN, !INVERT_Y_DIR);
|
||||
_delay_us(100);
|
||||
delayMicroseconds(STEPPER_SET_DIR_DELAY);
|
||||
for (uint8_t i = 0; i < st_backlash_y; i++)
|
||||
{
|
||||
WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
||||
_delay_us(100);
|
||||
WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||
_delay_us(900);
|
||||
STEP_NC_HI(Y_AXIS);
|
||||
STEPPER_MINIMUM_DELAY;
|
||||
STEP_NC_LO(Y_AXIS);
|
||||
_delay_us(900); // hard-coded jerk! *bad*
|
||||
}
|
||||
}
|
||||
last_dir_bits &= ~2;
|
||||
@ -603,44 +659,44 @@ FORCE_INLINE void stepper_tick_lowres()
|
||||
// Step in X axis
|
||||
counter_x.lo += current_block->steps_x.lo;
|
||||
if (counter_x.lo > 0) {
|
||||
WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
||||
STEP_NC_HI(X_AXIS);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
|
||||
STEP_NC_HI(X_DUP_AXIS);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
counter_x.lo -= current_block->step_event_count.lo;
|
||||
count_position[X_AXIS]+=count_direction[X_AXIS];
|
||||
WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
|
||||
STEP_NC_LO(X_AXIS);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
|
||||
STEP_NC_LO(X_DUP_AXIS);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
}
|
||||
// Step in Y axis
|
||||
counter_y.lo += current_block->steps_y.lo;
|
||||
if (counter_y.lo > 0) {
|
||||
WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
||||
STEP_NC_HI(Y_AXIS);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
|
||||
STEP_NC_HI(Y_DUP_AXIS);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
counter_y.lo -= current_block->step_event_count.lo;
|
||||
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
||||
WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||
STEP_NC_LO(Y_AXIS);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
|
||||
STEP_NC_LO(Y_DUP_AXIS);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
}
|
||||
// Step in Z axis
|
||||
counter_z.lo += current_block->steps_z.lo;
|
||||
if (counter_z.lo > 0) {
|
||||
WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
STEP_NC_HI(Z_AXIS);
|
||||
counter_z.lo -= current_block->step_event_count.lo;
|
||||
count_position[Z_AXIS]+=count_direction[Z_AXIS];
|
||||
WRITE_NC(Z_STEP_PIN, INVERT_Z_STEP_PIN);
|
||||
STEP_NC_LO(Z_AXIS);
|
||||
}
|
||||
// Step in E axis
|
||||
counter_e.lo += current_block->steps_e.lo;
|
||||
if (counter_e.lo > 0) {
|
||||
#ifndef LIN_ADVANCE
|
||||
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
STEP_NC_HI(E_AXIS);
|
||||
#endif /* LIN_ADVANCE */
|
||||
counter_e.lo -= current_block->step_event_count.lo;
|
||||
count_position[E_AXIS] += count_direction[E_AXIS];
|
||||
@ -650,7 +706,7 @@ FORCE_INLINE void stepper_tick_lowres()
|
||||
#ifdef FILAMENT_SENSOR
|
||||
fsensor_counter += count_direction[E_AXIS];
|
||||
#endif //FILAMENT_SENSOR
|
||||
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
|
||||
STEP_NC_LO(E_AXIS);
|
||||
#endif
|
||||
}
|
||||
if(++ step_events_completed.lo >= current_block->step_event_count.lo)
|
||||
@ -665,44 +721,44 @@ FORCE_INLINE void stepper_tick_highres()
|
||||
// Step in X axis
|
||||
counter_x.wide += current_block->steps_x.wide;
|
||||
if (counter_x.wide > 0) {
|
||||
WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
||||
STEP_NC_HI(X_AXIS);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
|
||||
STEP_NC_HI(X_DUP_AXIS);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
counter_x.wide -= current_block->step_event_count.wide;
|
||||
count_position[X_AXIS]+=count_direction[X_AXIS];
|
||||
WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
|
||||
STEP_NC_LO(X_AXIS);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
|
||||
STEP_NC_LO(X_DUP_AXIS);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
}
|
||||
// Step in Y axis
|
||||
counter_y.wide += current_block->steps_y.wide;
|
||||
if (counter_y.wide > 0) {
|
||||
WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
||||
STEP_NC_HI(Y_AXIS);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
|
||||
STEP_NC_HI(Y_DUP_AXIS);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
counter_y.wide -= current_block->step_event_count.wide;
|
||||
count_position[Y_AXIS]+=count_direction[Y_AXIS];
|
||||
WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||
STEP_NC_LO(Y_AXIS);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE_NC(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
|
||||
STEP_NC_LO(Y_DUP_AXIS);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
}
|
||||
// Step in Z axis
|
||||
counter_z.wide += current_block->steps_z.wide;
|
||||
if (counter_z.wide > 0) {
|
||||
WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
STEP_NC_HI(Z_AXIS);
|
||||
counter_z.wide -= current_block->step_event_count.wide;
|
||||
count_position[Z_AXIS]+=count_direction[Z_AXIS];
|
||||
WRITE_NC(Z_STEP_PIN, INVERT_Z_STEP_PIN);
|
||||
STEP_NC_LO(Z_AXIS);
|
||||
}
|
||||
// Step in E axis
|
||||
counter_e.wide += current_block->steps_e.wide;
|
||||
if (counter_e.wide > 0) {
|
||||
#ifndef LIN_ADVANCE
|
||||
WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
STEP_NC_HI(E_AXIS);
|
||||
#endif /* LIN_ADVANCE */
|
||||
counter_e.wide -= current_block->step_event_count.wide;
|
||||
count_position[E_AXIS]+=count_direction[E_AXIS];
|
||||
@ -712,7 +768,7 @@ FORCE_INLINE void stepper_tick_highres()
|
||||
#ifdef FILAMENT_SENSOR
|
||||
fsensor_counter += count_direction[E_AXIS];
|
||||
#endif //FILAMENT_SENSOR
|
||||
WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
|
||||
STEP_NC_LO(E_AXIS);
|
||||
#endif
|
||||
}
|
||||
if(++ step_events_completed.wide >= current_block->step_event_count.wide)
|
||||
@ -1014,9 +1070,9 @@ FORCE_INLINE void advance_isr_scheduler() {
|
||||
bool rev = (e_steps < 0);
|
||||
do
|
||||
{
|
||||
WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
|
||||
STEP_NC_HI(E_AXIS);
|
||||
e_steps += (rev? 1: -1);
|
||||
WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
|
||||
STEP_NC_LO(E_AXIS);
|
||||
#if defined(FILAMENT_SENSOR) && defined(PAT9125)
|
||||
fsensor_counter += (rev? -1: 1);
|
||||
#endif
|
||||
@ -1389,89 +1445,106 @@ void quickStop()
|
||||
#ifdef BABYSTEPPING
|
||||
void babystep(const uint8_t axis,const bool direction)
|
||||
{
|
||||
//MUST ONLY BE CALLED BY A ISR, it depends on that no other ISR interrupts this
|
||||
//store initial pin states
|
||||
switch(axis)
|
||||
{
|
||||
case X_AXIS:
|
||||
{
|
||||
enable_x();
|
||||
uint8_t old_x_dir_pin= READ(X_DIR_PIN); //if dualzstepper, both point to same direction.
|
||||
|
||||
//setup new step
|
||||
WRITE(X_DIR_PIN,(INVERT_X_DIR)^direction);
|
||||
|
||||
//perform step
|
||||
WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN);
|
||||
// MUST ONLY BE CALLED BY A ISR as stepper pins are manipulated directly.
|
||||
// note: when switching direction no delay is inserted at the end when the
|
||||
// original is restored. We assume enough time passes as the function
|
||||
// returns and the stepper is manipulated again (to avoid dead times)
|
||||
switch(axis)
|
||||
{
|
||||
case X_AXIS:
|
||||
{
|
||||
enable_x();
|
||||
uint8_t old_x_dir_pin = READ(X_DIR_PIN); //if dualzstepper, both point to same direction.
|
||||
uint8_t new_x_dir_pin = (INVERT_X_DIR)^direction;
|
||||
|
||||
//setup new step
|
||||
if (new_x_dir_pin != old_x_dir_pin) {
|
||||
WRITE_NC(X_DIR_PIN, new_x_dir_pin);
|
||||
delayMicroseconds(STEPPER_SET_DIR_DELAY);
|
||||
}
|
||||
|
||||
//perform step
|
||||
STEP_NC_HI(X_AXIS);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
delayMicroseconds(1);
|
||||
WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
|
||||
STEP_NC_HI(X_DUP_AXIS);
|
||||
#endif
|
||||
STEPPER_MINIMUM_DELAY;
|
||||
STEP_NC_LO(X_AXIS);
|
||||
#ifdef DEBUG_XSTEP_DUP_PIN
|
||||
WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
|
||||
#endif //DEBUG_XSTEP_DUP_PIN
|
||||
STEP_NC_LO(X_DUP_AXIS);
|
||||
#endif
|
||||
|
||||
//get old pin state back.
|
||||
WRITE(X_DIR_PIN,old_x_dir_pin);
|
||||
}
|
||||
break;
|
||||
case Y_AXIS:
|
||||
{
|
||||
enable_y();
|
||||
uint8_t old_y_dir_pin= READ(Y_DIR_PIN); //if dualzstepper, both point to same direction.
|
||||
|
||||
//setup new step
|
||||
WRITE(Y_DIR_PIN,(INVERT_Y_DIR)^direction);
|
||||
|
||||
//perform step
|
||||
WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
|
||||
//get old pin state back.
|
||||
WRITE_NC(X_DIR_PIN, old_x_dir_pin);
|
||||
}
|
||||
break;
|
||||
|
||||
case Y_AXIS:
|
||||
{
|
||||
enable_y();
|
||||
uint8_t old_y_dir_pin = READ(Y_DIR_PIN); //if dualzstepper, both point to same direction.
|
||||
uint8_t new_y_dir_pin = (INVERT_Y_DIR)^direction;
|
||||
|
||||
//setup new step
|
||||
if (new_y_dir_pin != old_y_dir_pin) {
|
||||
WRITE_NC(Y_DIR_PIN, new_y_dir_pin);
|
||||
delayMicroseconds(STEPPER_SET_DIR_DELAY);
|
||||
}
|
||||
|
||||
//perform step
|
||||
STEP_NC_HI(Y_AXIS);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
delayMicroseconds(1);
|
||||
WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
|
||||
STEP_NC_HI(Y_DUP_AXIS);
|
||||
#endif
|
||||
STEPPER_MINIMUM_DELAY;
|
||||
STEP_NC_LO(Y_AXIS);
|
||||
#ifdef DEBUG_YSTEP_DUP_PIN
|
||||
WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
|
||||
#endif //DEBUG_YSTEP_DUP_PIN
|
||||
STEP_NC_LO(Y_DUP_AXIS);
|
||||
#endif
|
||||
|
||||
//get old pin state back.
|
||||
WRITE(Y_DIR_PIN,old_y_dir_pin);
|
||||
//get old pin state back.
|
||||
WRITE_NC(Y_DIR_PIN, old_y_dir_pin);
|
||||
}
|
||||
break;
|
||||
|
||||
}
|
||||
break;
|
||||
|
||||
case Z_AXIS:
|
||||
{
|
||||
enable_z();
|
||||
uint8_t old_z_dir_pin= READ(Z_DIR_PIN); //if dualzstepper, both point to same direction.
|
||||
//setup new step
|
||||
WRITE(Z_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Z2_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
|
||||
#endif
|
||||
//perform step
|
||||
WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
|
||||
#endif
|
||||
delayMicroseconds(1);
|
||||
WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN);
|
||||
#endif
|
||||
case Z_AXIS:
|
||||
{
|
||||
enable_z();
|
||||
uint8_t old_z_dir_pin = READ(Z_DIR_PIN); //if dualzstepper, both point to same direction.
|
||||
uint8_t new_z_dir_pin = (INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z;
|
||||
|
||||
//get old pin state back.
|
||||
WRITE(Z_DIR_PIN,old_z_dir_pin);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE(Z2_DIR_PIN,old_z_dir_pin);
|
||||
#endif
|
||||
//setup new step
|
||||
if (new_z_dir_pin != old_z_dir_pin) {
|
||||
WRITE_NC(Z_DIR_PIN, new_z_dir_pin);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE_NC(Z2_DIR_PIN, new_z_dir_pin);
|
||||
#endif
|
||||
delayMicroseconds(STEPPER_SET_DIR_DELAY);
|
||||
}
|
||||
|
||||
}
|
||||
break;
|
||||
|
||||
default: break;
|
||||
}
|
||||
//perform step
|
||||
STEP_NC_HI(Z_AXIS);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
STEP_NC_HI(Z2_AXIS);
|
||||
#endif
|
||||
STEPPER_MINIMUM_DELAY;
|
||||
STEP_NC_LO(Z_AXIS);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
STEP_NC_LO(Z2_AXIS);
|
||||
#endif
|
||||
|
||||
//get old pin state back.
|
||||
if (new_z_dir_pin != old_z_dir_pin) {
|
||||
WRITE_NC(Z_DIR_PIN, old_z_dir_pin);
|
||||
#ifdef Z_DUAL_STEPPER_DRIVERS
|
||||
WRITE_NC(Z2_DIR_PIN, old_z_dir_pin);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
default: break;
|
||||
}
|
||||
}
|
||||
#endif //BABYSTEPPING
|
||||
|
||||
|
@ -3,9 +3,10 @@
|
||||
#include <avr/io.h>
|
||||
#include <util/delay.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include "stdbool.h"
|
||||
#include "Configuration_prusa.h"
|
||||
#include "pins.h"
|
||||
#include "io_atmega2560.h"
|
||||
#include "fastio.h"
|
||||
|
||||
#ifdef SWI2C_SCL
|
||||
|
||||
@ -22,75 +23,75 @@ void __delay(void)
|
||||
|
||||
void swi2c_init(void)
|
||||
{
|
||||
PIN_OUT(SWI2C_SDA);
|
||||
PIN_OUT(SWI2C_SCL);
|
||||
PIN_SET(SWI2C_SDA);
|
||||
PIN_SET(SWI2C_SCL);
|
||||
WRITE(SWI2C_SDA, 1);
|
||||
WRITE(SWI2C_SCL, 1);
|
||||
SET_OUTPUT(SWI2C_SDA);
|
||||
SET_OUTPUT(SWI2C_SCL);
|
||||
uint8_t i; for (i = 0; i < 100; i++)
|
||||
__delay();
|
||||
}
|
||||
|
||||
void swi2c_start(void)
|
||||
{
|
||||
PIN_CLR(SWI2C_SDA);
|
||||
WRITE(SWI2C_SDA, 0);
|
||||
__delay();
|
||||
PIN_CLR(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 0);
|
||||
__delay();
|
||||
}
|
||||
|
||||
void swi2c_stop(void)
|
||||
{
|
||||
PIN_SET(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 1);
|
||||
__delay();
|
||||
PIN_SET(SWI2C_SDA);
|
||||
WRITE(SWI2C_SDA, 1);
|
||||
__delay();
|
||||
}
|
||||
|
||||
void swi2c_ack(void)
|
||||
{
|
||||
PIN_CLR(SWI2C_SDA);
|
||||
WRITE(SWI2C_SDA, 0);
|
||||
__delay();
|
||||
PIN_SET(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 1);
|
||||
__delay();
|
||||
PIN_CLR(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 0);
|
||||
__delay();
|
||||
}
|
||||
|
||||
uint8_t swi2c_wait_ack()
|
||||
{
|
||||
PIN_INP(SWI2C_SDA);
|
||||
SET_INPUT(SWI2C_SDA);
|
||||
__delay();
|
||||
// PIN_SET(SWI2C_SDA);
|
||||
// WRITE(SWI2C_SDA, 1);
|
||||
__delay();
|
||||
PIN_SET(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 1);
|
||||
// __delay();
|
||||
uint8_t ack = 0;
|
||||
uint16_t ackto = SWI2C_TMO;
|
||||
while (!(ack = (PIN_GET(SWI2C_SDA)?0:1)) && ackto--) __delay();
|
||||
PIN_CLR(SWI2C_SCL);
|
||||
while (!(ack = (!READ(SWI2C_SDA))) && ackto--) __delay();
|
||||
WRITE(SWI2C_SCL, 0);
|
||||
__delay();
|
||||
PIN_OUT(SWI2C_SDA);
|
||||
SET_OUTPUT(SWI2C_SDA);
|
||||
__delay();
|
||||
PIN_CLR(SWI2C_SDA);
|
||||
WRITE(SWI2C_SDA, 0);
|
||||
__delay();
|
||||
return ack;
|
||||
}
|
||||
|
||||
uint8_t swi2c_read(void)
|
||||
{
|
||||
PIN_SET(SWI2C_SDA);
|
||||
WRITE(SWI2C_SDA, 1);
|
||||
__delay();
|
||||
PIN_INP(SWI2C_SDA);
|
||||
SET_INPUT(SWI2C_SDA);
|
||||
uint8_t data = 0;
|
||||
int8_t bit; for (bit = 7; bit >= 0; bit--)
|
||||
{
|
||||
PIN_SET(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 1);
|
||||
__delay();
|
||||
data |= (PIN_GET(SWI2C_SDA)?1:0) << bit;
|
||||
PIN_CLR(SWI2C_SCL);
|
||||
data |= (READ(SWI2C_SDA)) << bit;
|
||||
WRITE(SWI2C_SCL, 0);
|
||||
__delay();
|
||||
}
|
||||
PIN_OUT(SWI2C_SDA);
|
||||
SET_OUTPUT(SWI2C_SDA);
|
||||
return data;
|
||||
}
|
||||
|
||||
@ -98,12 +99,11 @@ void swi2c_write(uint8_t data)
|
||||
{
|
||||
int8_t bit; for (bit = 7; bit >= 0; bit--)
|
||||
{
|
||||
if (data & (1 << bit)) PIN_SET(SWI2C_SDA);
|
||||
else PIN_CLR(SWI2C_SDA);
|
||||
WRITE(SWI2C_SDA, data & _BV(bit));
|
||||
__delay();
|
||||
PIN_SET(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 1);
|
||||
__delay();
|
||||
PIN_CLR(SWI2C_SCL);
|
||||
WRITE(SWI2C_SCL, 0);
|
||||
__delay();
|
||||
}
|
||||
}
|
||||
|
@ -30,6 +30,7 @@
|
||||
|
||||
|
||||
#include "Marlin.h"
|
||||
#include "cmdqueue.h"
|
||||
#include "ultralcd.h"
|
||||
#include "sound.h"
|
||||
#include "temperature.h"
|
||||
@ -238,7 +239,7 @@ bool extruder_altfan_detect()
|
||||
uint8_t overrideVal = eeprom_read_byte((uint8_t *)EEPROM_ALTFAN_OVERRIDE);
|
||||
if (overrideVal == EEPROM_EMPTY_VALUE)
|
||||
{
|
||||
overrideVal = 0;
|
||||
overrideVal = (calibration_status() == CALIBRATION_STATUS_CALIBRATED) ? 1 : 0;
|
||||
eeprom_update_byte((uint8_t *)EEPROM_ALTFAN_OVERRIDE, overrideVal);
|
||||
}
|
||||
altfanStatus.altfanOverride = overrideVal;
|
||||
@ -521,7 +522,7 @@ void setExtruderAutoFanState(uint8_t state)
|
||||
//the fan to either On or Off during certain tests/errors.
|
||||
|
||||
fanState = state;
|
||||
uint8_t newFanSpeed = 0;
|
||||
newFanSpeed = 0;
|
||||
if (fanState & 0x01)
|
||||
{
|
||||
#ifdef EXTRUDER_ALTFAN_DETECT
|
||||
@ -632,7 +633,6 @@ void fanSpeedError(unsigned char _fan) {
|
||||
fanSpeedErrorBeep(PSTR("Print fan speed is lower than expected"), MSG_FANCHECK_PRINT);
|
||||
break;
|
||||
}
|
||||
// SERIAL_PROTOCOLLNRPGM(MSG_OK); //This ok messes things up with octoprint.
|
||||
}
|
||||
#endif //(defined(TACH_0) && TACH_0 >-1) || (defined(TACH_1) && TACH_1 > -1)
|
||||
|
||||
@ -2325,11 +2325,22 @@ float unscalePID_d(float d)
|
||||
//!
|
||||
//! @retval true firmware should do temperature compensation and allow calibration
|
||||
//! @retval false PINDA thermistor is not detected, disable temperature compensation and calibration
|
||||
//! @retval true/false when forced via LCD menu Settings->HW Setup->SuperPINDA
|
||||
//!
|
||||
bool has_temperature_compensation()
|
||||
{
|
||||
#ifdef DETECT_SUPERPINDA
|
||||
return (current_temperature_pinda >= PINDA_MINTEMP) ? true : false;
|
||||
#ifdef SUPERPINDA_SUPPORT
|
||||
#ifdef PINDA_TEMP_COMP
|
||||
uint8_t pinda_temp_compensation = eeprom_read_byte((uint8_t*)EEPROM_PINDA_TEMP_COMPENSATION);
|
||||
if (pinda_temp_compensation == EEPROM_EMPTY_VALUE) //Unkown PINDA temp compenstation, so check it.
|
||||
{
|
||||
#endif //PINDA_TEMP_COMP
|
||||
return (current_temperature_pinda >= PINDA_MINTEMP) ? true : false;
|
||||
#ifdef PINDA_TEMP_COMP
|
||||
}
|
||||
else if (pinda_temp_compensation == 0) return true; //Overwritten via LCD menu SuperPINDA [No]
|
||||
else return false; //Overwritten via LCD menu SuperPINDA [YES]
|
||||
#endif //PINDA_TEMP_COMP
|
||||
#else
|
||||
return true;
|
||||
#endif
|
||||
|
@ -9,9 +9,6 @@
|
||||
|
||||
#include <avr/io.h>
|
||||
#include <avr/interrupt.h>
|
||||
#include "io_atmega2560.h"
|
||||
|
||||
#define BEEPER 84
|
||||
|
||||
void timer0_init(void)
|
||||
{
|
||||
|
@ -428,6 +428,11 @@ 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 = (mres != 0); // intpol to 256 only if microsteps aren't 256
|
||||
#ifdef TMC2130_DEDGE_STEPPING
|
||||
uint8_t dedge = 1;
|
||||
#else
|
||||
uint8_t dedge = 0;
|
||||
#endif
|
||||
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
|
||||
@ -437,6 +442,9 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_
|
||||
uint8_t tbl = tmc2130_chopper_config[axis].tbl; //blanking time, original value = 2
|
||||
if (axis == E_AXIS)
|
||||
{
|
||||
#if defined(TMC2130_INTPOL_E) && (TMC2130_INTPOL_E == 0)
|
||||
intpol = 0;
|
||||
#endif
|
||||
#ifdef TMC2130_CNSTOFF_E
|
||||
// fd = 0 (slow decay only)
|
||||
hstrt = 0; //fd0..2
|
||||
@ -447,16 +455,26 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_
|
||||
// toff = TMC2130_TOFF_E; // toff = 3-5
|
||||
// rndtf = 1;
|
||||
}
|
||||
#if defined(TMC2130_INTPOL_XY) && (TMC2130_INTPOL_XY == 0)
|
||||
else if (axis == X_AXIS || axis == Y_AXIS) {
|
||||
intpol = 0;
|
||||
}
|
||||
#endif
|
||||
#if defined(TMC2130_INTPOL_Z) && (TMC2130_INTPOL_Z == 0)
|
||||
else if (axis == Z_AXIS) {
|
||||
intpol = 0;
|
||||
}
|
||||
#endif
|
||||
// DBG(_n("tmc2130_setup_chopper(axis=%hhd, mres=%hhd, curh=%hhd, curr=%hhd\n"), axis, mres, current_h, current_r);
|
||||
// DBG(_n(" toff=%hhd, hstr=%hhd, hend=%hhd, tbl=%hhd\n"), toff, hstrt, hend, tbl);
|
||||
if (current_r <= 31)
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 1, 0, 0, 0, mres, intpol, 0, 0);
|
||||
tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 1, 0, 0, 0, mres, intpol, dedge, 0);
|
||||
tmc2130_wr(axis, TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((current_r & 0x1f) << 8) | (current_h & 0x1f));
|
||||
}
|
||||
else
|
||||
{
|
||||
tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 0, 0, 0, 0, mres, intpol, 0, 0);
|
||||
tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 0, 0, 0, 0, mres, intpol, dedge, 0);
|
||||
tmc2130_wr(axis, TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((current_r >> 1) & 0x1f) << 8) | ((current_h >> 1) & 0x1f));
|
||||
}
|
||||
}
|
||||
@ -678,25 +696,32 @@ static uint8_t tmc2130_rx(uint8_t axis, uint8_t addr, uint32_t* rval)
|
||||
#define _GET_PWR_Z (READ(Z_ENABLE_PIN) == Z_ENABLE_ON)
|
||||
#define _GET_PWR_E (READ(E0_ENABLE_PIN) == E_ENABLE_ON)
|
||||
|
||||
#define _SET_PWR_X(ena) { WRITE(X_ENABLE_PIN, ena?X_ENABLE_ON:!X_ENABLE_ON); asm("nop"); }
|
||||
#define _SET_PWR_Y(ena) { WRITE(Y_ENABLE_PIN, ena?Y_ENABLE_ON:!Y_ENABLE_ON); asm("nop"); }
|
||||
#define _SET_PWR_Z(ena) { WRITE(Z_ENABLE_PIN, ena?Z_ENABLE_ON:!Z_ENABLE_ON); asm("nop"); }
|
||||
#define _SET_PWR_E(ena) { WRITE(E0_ENABLE_PIN, ena?E_ENABLE_ON:!E_ENABLE_ON); asm("nop"); }
|
||||
#define _SET_PWR_X(ena) WRITE(X_ENABLE_PIN, ena?X_ENABLE_ON:!X_ENABLE_ON)
|
||||
#define _SET_PWR_Y(ena) WRITE(Y_ENABLE_PIN, ena?Y_ENABLE_ON:!Y_ENABLE_ON)
|
||||
#define _SET_PWR_Z(ena) WRITE(Z_ENABLE_PIN, ena?Z_ENABLE_ON:!Z_ENABLE_ON)
|
||||
#define _SET_PWR_E(ena) WRITE(E0_ENABLE_PIN, ena?E_ENABLE_ON:!E_ENABLE_ON)
|
||||
|
||||
#define _GET_DIR_X (READ(X_DIR_PIN) == INVERT_X_DIR)
|
||||
#define _GET_DIR_Y (READ(Y_DIR_PIN) == INVERT_Y_DIR)
|
||||
#define _GET_DIR_Z (READ(Z_DIR_PIN) == INVERT_Z_DIR)
|
||||
#define _GET_DIR_E (READ(E0_DIR_PIN) == INVERT_E0_DIR)
|
||||
|
||||
#define _SET_DIR_X(dir) { WRITE(X_DIR_PIN, dir?INVERT_X_DIR:!INVERT_X_DIR); asm("nop"); }
|
||||
#define _SET_DIR_Y(dir) { WRITE(Y_DIR_PIN, dir?INVERT_Y_DIR:!INVERT_Y_DIR); asm("nop"); }
|
||||
#define _SET_DIR_Z(dir) { WRITE(Z_DIR_PIN, dir?INVERT_Z_DIR:!INVERT_Z_DIR); asm("nop"); }
|
||||
#define _SET_DIR_E(dir) { WRITE(E0_DIR_PIN, dir?INVERT_E0_DIR:!INVERT_E0_DIR); asm("nop"); }
|
||||
#define _SET_DIR_X(dir) WRITE(X_DIR_PIN, dir?INVERT_X_DIR:!INVERT_X_DIR)
|
||||
#define _SET_DIR_Y(dir) WRITE(Y_DIR_PIN, dir?INVERT_Y_DIR:!INVERT_Y_DIR)
|
||||
#define _SET_DIR_Z(dir) WRITE(Z_DIR_PIN, dir?INVERT_Z_DIR:!INVERT_Z_DIR)
|
||||
#define _SET_DIR_E(dir) WRITE(E0_DIR_PIN, dir?INVERT_E0_DIR:!INVERT_E0_DIR)
|
||||
|
||||
#define _DO_STEP_X { WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); asm("nop"); WRITE(X_STEP_PIN, INVERT_X_STEP_PIN); asm("nop"); }
|
||||
#define _DO_STEP_Y { WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN); asm("nop"); WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN); asm("nop"); }
|
||||
#define _DO_STEP_Z { WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); asm("nop"); WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN); asm("nop"); }
|
||||
#define _DO_STEP_E { WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN); asm("nop"); WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN); asm("nop"); }
|
||||
#ifdef TMC2130_DEDGE_STEPPING
|
||||
#define _DO_STEP_X TOGGLE(X_STEP_PIN)
|
||||
#define _DO_STEP_Y TOGGLE(Y_STEP_PIN)
|
||||
#define _DO_STEP_Z TOGGLE(Z_STEP_PIN)
|
||||
#define _DO_STEP_E TOGGLE(E0_STEP_PIN)
|
||||
#else
|
||||
#define _DO_STEP_X { WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(X_STEP_PIN, INVERT_X_STEP_PIN); }
|
||||
#define _DO_STEP_Y { WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN); }
|
||||
#define _DO_STEP_Z { WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN); }
|
||||
#define _DO_STEP_E { WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN); }
|
||||
#endif
|
||||
|
||||
|
||||
uint16_t tmc2130_get_res(uint8_t axis)
|
||||
@ -737,6 +762,7 @@ void tmc2130_set_pwr(uint8_t axis, uint8_t pwr)
|
||||
case Z_AXIS: _SET_PWR_Z(pwr); break;
|
||||
case E_AXIS: _SET_PWR_E(pwr); break;
|
||||
}
|
||||
delayMicroseconds(TMC2130_SET_PWR_DELAY);
|
||||
}
|
||||
|
||||
uint8_t tmc2130_get_inv(uint8_t axis)
|
||||
@ -773,6 +799,7 @@ void tmc2130_set_dir(uint8_t axis, uint8_t dir)
|
||||
case Z_AXIS: _SET_DIR_Z(dir); break;
|
||||
case E_AXIS: _SET_DIR_E(dir); break;
|
||||
}
|
||||
delayMicroseconds(TMC2130_SET_DIR_DELAY);
|
||||
}
|
||||
|
||||
void tmc2130_do_step(uint8_t axis)
|
||||
@ -788,8 +815,8 @@ void tmc2130_do_step(uint8_t axis)
|
||||
|
||||
void tmc2130_do_steps(uint8_t axis, uint16_t steps, uint8_t dir, uint16_t delay_us)
|
||||
{
|
||||
tmc2130_set_dir(axis, dir);
|
||||
delayMicroseconds(100);
|
||||
if (tmc2130_get_dir(axis) != dir)
|
||||
tmc2130_set_dir(axis, dir);
|
||||
while (steps--)
|
||||
{
|
||||
tmc2130_do_step(axis);
|
||||
@ -820,7 +847,6 @@ void tmc2130_goto_step(uint8_t axis, uint8_t step, uint8_t dir, uint16_t delay_u
|
||||
cnt = steps;
|
||||
}
|
||||
tmc2130_set_dir(axis, dir);
|
||||
delayMicroseconds(100);
|
||||
mscnt = tmc2130_rd_MSCNT(axis);
|
||||
while ((cnt--) && ((mscnt >> shift) != step))
|
||||
{
|
||||
@ -996,11 +1022,11 @@ bool tmc2130_home_calibrate(uint8_t axis)
|
||||
uint8_t val[16];
|
||||
homeaxis(axis, 16, step);
|
||||
bubblesort_uint8(step, 16, 0);
|
||||
printf_P(PSTR("sorted samples:\n"));
|
||||
puts_P(PSTR("sorted samples:"));
|
||||
for (uint8_t i = 0; i < 16; i++)
|
||||
printf_P(PSTR(" i=%2d step=%2d\n"), i, step[i]);
|
||||
uint8_t cl = clusterize_uint8(step, 16, cnt, val, 1);
|
||||
printf_P(PSTR("clusters:\n"));
|
||||
puts_P(PSTR("clusters:"));
|
||||
for (uint8_t i = 0; i < cl; i++)
|
||||
printf_P(PSTR(" i=%2d cnt=%2d val=%2d\n"), i, cnt[i], val[i]);
|
||||
bubblesort_uint8(cnt, cl, val);
|
||||
|
@ -29,6 +29,18 @@ extern uint8_t tmc2130_sg_homing_axes_mask;
|
||||
#define TMC2130_WAVE_FAC1000_MAX 200
|
||||
#define TMC2130_WAVE_FAC1000_STP 1
|
||||
|
||||
#define TMC2130_MINIMUM_PULSE 0 // minimum pulse width in uS
|
||||
#define TMC2130_SET_DIR_DELAY 20 // minimum delay after setting direction in uS
|
||||
#define TMC2130_SET_PWR_DELAY 0 // minimum delay after changing pwr mode in uS
|
||||
|
||||
#ifdef TMC2130_DEDGE_STEPPING
|
||||
#define TMC2130_MINIMUM_DELAY //NOP
|
||||
#elif TMC2130_MINIMUM_PULSE == 0
|
||||
#define TMC2130_MINIMUM_DELAY asm("nop")
|
||||
#else
|
||||
#define TMC2130_MINIMUM_DELAY delayMicroseconds(TMC2130_MINIMUM_PULSE)
|
||||
#endif
|
||||
|
||||
extern uint8_t tmc2130_home_enabled;
|
||||
extern uint8_t tmc2130_home_origin[2];
|
||||
extern uint8_t tmc2130_home_bsteps[2];
|
||||
|
@ -9,6 +9,7 @@
|
||||
|
||||
#include "pins.h"
|
||||
#include "fastio.h"
|
||||
#include "macros.h"
|
||||
|
||||
void timer4_init(void)
|
||||
{
|
||||
@ -70,7 +71,7 @@ ISR(TIMER4_OVF_vect)
|
||||
WRITE(BEEPER, 0);
|
||||
}
|
||||
|
||||
void tone4(__attribute__((unused)) uint8_t _pin, uint16_t frequency)
|
||||
void tone4(_UNUSED uint8_t _pin, uint16_t frequency)
|
||||
{
|
||||
//this ocr and prescalarbits calculation is taken from the Arduino core and simplified for one type of timer only
|
||||
uint8_t prescalarbits = 0b001;
|
||||
@ -96,7 +97,7 @@ void tone4(__attribute__((unused)) uint8_t _pin, uint16_t frequency)
|
||||
CRITICAL_SECTION_END;
|
||||
}
|
||||
|
||||
void noTone4(__attribute__((unused)) uint8_t _pin)
|
||||
void noTone4(_UNUSED uint8_t _pin)
|
||||
{
|
||||
CRITICAL_SECTION_START;
|
||||
// Revert prescaler to CLK/1024
|
||||
|
@ -4,6 +4,7 @@
|
||||
#include <avr/interrupt.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include "rbuf.h"
|
||||
#include "macros.h"
|
||||
|
||||
#define UART2_BAUD 115200
|
||||
#define UART_BAUD_SELECT(baudRate,xtalCpu) (((float)(xtalCpu))/(((float)(baudRate))*8.0)-1.0+0.5)
|
||||
@ -16,7 +17,7 @@ uint8_t uart2_ibuf[14] = {0, 0};
|
||||
FILE _uart2io = {0};
|
||||
|
||||
|
||||
int uart2_putchar(char c, FILE *stream __attribute__((unused)))
|
||||
int uart2_putchar(char c, _UNUSED FILE *stream)
|
||||
{
|
||||
while (!uart2_txready);
|
||||
UDR2 = c; // transmit byte
|
||||
@ -25,7 +26,7 @@ int uart2_putchar(char c, FILE *stream __attribute__((unused)))
|
||||
return 0;
|
||||
}
|
||||
|
||||
int uart2_getchar(FILE *stream __attribute__((unused)))
|
||||
int uart2_getchar(_UNUSED FILE *stream)
|
||||
{
|
||||
if (rbuf_empty(uart2_ibuf)) return -1;
|
||||
return rbuf_get(uart2_ibuf);
|
||||
@ -78,7 +79,7 @@ ISR(USART2_RX_vect)
|
||||
if (rbuf_put(uart2_ibuf, UDR2) < 0) // put received byte to buffer
|
||||
{ //rx buffer full
|
||||
//uart2_rx_clr(); //for sure, clear input buffer
|
||||
printf_P(PSTR("USART2 rx Full!!!\n"));
|
||||
puts_P(PSTR("USART2 rx Full!!!"));
|
||||
}
|
||||
}
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -47,7 +47,6 @@ void lcd_pause_print();
|
||||
void lcd_resume_print();
|
||||
void lcd_print_stop();
|
||||
void prusa_statistics(int _message, uint8_t _col_nr = 0);
|
||||
void lcd_confirm_print();
|
||||
unsigned char lcd_choose_color();
|
||||
void lcd_load_filament_color_check();
|
||||
//void lcd_mylang();
|
||||
@ -127,7 +126,6 @@ extern CustomMsg custom_message_type;
|
||||
extern unsigned int custom_message_state;
|
||||
|
||||
extern uint8_t farm_mode;
|
||||
extern int farm_no;
|
||||
extern int farm_timer;
|
||||
extern uint8_t farm_status;
|
||||
|
||||
@ -207,6 +205,7 @@ void lcd_farm_sdcard_menu_w();
|
||||
|
||||
void lcd_wait_for_heater();
|
||||
void lcd_wait_for_cool_down();
|
||||
void lcd_move_e(); // NOT static due to usage in Marlin_main
|
||||
void lcd_extr_cal_reset();
|
||||
|
||||
void lcd_temp_cal_show_result(bool result);
|
||||
@ -262,4 +261,8 @@ void lcd_wizard(WizState state);
|
||||
extern void lcd_experimental_toggle();
|
||||
extern void lcd_experimental_menu();
|
||||
|
||||
#ifdef PINDA_TEMP_COMP
|
||||
extern void lcd_pinda_temp_compensation_toggle();
|
||||
#endif //PINDA_TEMP_COMP
|
||||
|
||||
#endif //ULTRALCD_H
|
||||
|
@ -428,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("G-code sliced for a different printer type. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_T(MSG_GCODE_DIFF_PRINTER_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("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."));
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_GCODE_DIFF_PRINTER_CANCELLED));
|
||||
lcd_print_stop();
|
||||
break;
|
||||
case ClCheckModel::_None:
|
||||
@ -577,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("G-code sliced for a different printer type. Continue?"));
|
||||
lcd_display_message_fullscreen_P(_T(MSG_GCODE_DIFF_PRINTER_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("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."));
|
||||
lcd_show_fullscreen_message_and_wait_P(_T(MSG_GCODE_DIFF_PRINTER_CANCELLED));
|
||||
lcd_print_stop();
|
||||
break;
|
||||
case ClCheckModel::_None:
|
||||
|
@ -51,6 +51,7 @@ enum class ClNozzleDiameter:uint_least8_t
|
||||
_Diameter_250=25,
|
||||
_Diameter_400=40,
|
||||
_Diameter_600=60,
|
||||
_Diameter_800=80,
|
||||
_Diameter_Undef=EEPROM_EMPTY_VALUE
|
||||
};
|
||||
|
||||
|
@ -326,6 +326,10 @@ PREHEAT SETTINGS
|
||||
#define PLA_PREHEAT_HPB_TEMP 55
|
||||
#define PLA_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
#define PVB_PREHEAT_FAN_SPEED 0
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
#define ASA_PREHEAT_FAN_SPEED 0
|
||||
|
@ -323,6 +323,9 @@ PREHEAT SETTINGS
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 55
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
|
@ -175,6 +175,9 @@
|
||||
#if BED_MINTEMP_DELAY>USHRT_MAX
|
||||
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
|
||||
#endif
|
||||
#define SUPERPINDA_SUPPORT
|
||||
#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
|
||||
#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
@ -381,6 +384,9 @@
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
|
@ -176,6 +176,9 @@
|
||||
#if BED_MINTEMP_DELAY>USHRT_MAX
|
||||
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
|
||||
#endif
|
||||
#define SUPERPINDA_SUPPORT
|
||||
#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
|
||||
#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
@ -382,6 +385,9 @@
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
|
@ -175,6 +175,9 @@
|
||||
#if BED_MINTEMP_DELAY>USHRT_MAX
|
||||
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
|
||||
#endif
|
||||
#define SUPERPINDA_SUPPORT
|
||||
#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
|
||||
#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
@ -381,6 +384,9 @@
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
|
@ -176,6 +176,9 @@
|
||||
#if BED_MINTEMP_DELAY>USHRT_MAX
|
||||
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
|
||||
#endif
|
||||
#define SUPERPINDA_SUPPORT
|
||||
#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
|
||||
#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
|
||||
|
||||
// Maxtemps
|
||||
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
|
||||
@ -382,6 +385,9 @@
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
|
@ -266,9 +266,9 @@
|
||||
#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_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
|
||||
#define TMC2130_DEDGE_STEPPING
|
||||
|
||||
//#define TMC2130_SERVICE_CODES_M910_M918
|
||||
|
||||
@ -294,8 +294,9 @@
|
||||
#if BED_MINTEMP_DELAY>USHRT_MAX
|
||||
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
|
||||
#endif
|
||||
#define DETECT_SUPERPINDA
|
||||
#define PINDA_MINTEMP BED_MINTEMP
|
||||
#define SUPERPINDA_SUPPORT
|
||||
#define PINDA_MINTEMP 10
|
||||
//#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
|
||||
#define AMBIENT_MINTEMP -30
|
||||
|
||||
// Maxtemps
|
||||
@ -497,6 +498,9 @@
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
|
@ -268,9 +268,9 @@
|
||||
#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_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
|
||||
#define TMC2130_DEDGE_STEPPING
|
||||
|
||||
//#define TMC2130_SERVICE_CODES_M910_M918
|
||||
|
||||
@ -296,8 +296,9 @@
|
||||
#if BED_MINTEMP_DELAY>USHRT_MAX
|
||||
#error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
|
||||
#endif
|
||||
#define DETECT_SUPERPINDA
|
||||
#define PINDA_MINTEMP BED_MINTEMP
|
||||
#define SUPERPINDA_SUPPORT
|
||||
#define PINDA_MINTEMP 10
|
||||
//#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
|
||||
#define AMBIENT_MINTEMP -30
|
||||
|
||||
// Maxtemps
|
||||
@ -501,6 +502,9 @@
|
||||
#define PLA_PREHEAT_HOTEND_TEMP 215
|
||||
#define PLA_PREHEAT_HPB_TEMP 60
|
||||
|
||||
#define PVB_PREHEAT_HOTEND_TEMP 215
|
||||
#define PVB_PREHEAT_HPB_TEMP 75
|
||||
|
||||
#define ASA_PREHEAT_HOTEND_TEMP 260
|
||||
#define ASA_PREHEAT_HPB_TEMP 105
|
||||
|
||||
|
@ -3,8 +3,8 @@
|
||||
#include "w25x20cl.h"
|
||||
#include <avr/io.h>
|
||||
#include <avr/pgmspace.h>
|
||||
#include "io_atmega2560.h"
|
||||
#include "spi.h"
|
||||
#include "fastio.h"
|
||||
|
||||
#define _MFRID 0xEF
|
||||
#define _DEVID 0x11
|
||||
@ -31,8 +31,8 @@
|
||||
#define _CMD_JEDEC_ID 0x9f
|
||||
#define _CMD_RD_UID 0x4b
|
||||
|
||||
#define _CS_LOW() PORT(W25X20CL_PIN_CS) &= ~__MSK(W25X20CL_PIN_CS)
|
||||
#define _CS_HIGH() PORT(W25X20CL_PIN_CS) |= __MSK(W25X20CL_PIN_CS)
|
||||
#define _CS_LOW() WRITE(W25X20CL_PIN_CS, 0)
|
||||
#define _CS_HIGH() WRITE(W25X20CL_PIN_CS, 1)
|
||||
|
||||
//#define _SPI_TX swspi_tx
|
||||
//#define _SPI_RX swspi_rx
|
||||
@ -45,8 +45,8 @@ int w25x20cl_mfrid_devid(void);
|
||||
|
||||
int8_t w25x20cl_init(void)
|
||||
{
|
||||
PIN_OUT(W25X20CL_PIN_CS);
|
||||
_CS_HIGH();
|
||||
SET_OUTPUT(W25X20CL_PIN_CS);
|
||||
W25X20CL_SPI_ENTER();
|
||||
if (!w25x20cl_mfrid_devid()) return 0;
|
||||
return 1;
|
||||
|
1119
Firmware/xyzcal.cpp
1119
Firmware/xyzcal.cpp
File diff suppressed because it is too large
Load Diff
@ -17,20 +17,6 @@ extern bool xyzcal_spiral8(int16_t cx, int16_t cy, int16_t z0, int16_t dz, int16
|
||||
|
||||
//extern int8_t xyzcal_meassure_pinda_hysterezis(int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t samples);
|
||||
|
||||
extern void xyzcal_scan_pixels_32x32(int16_t cx, int16_t cy, int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t* pixels);
|
||||
|
||||
extern void xyzcal_histo_pixels_32x32(uint8_t* pixels, uint16_t* histo);
|
||||
|
||||
extern void xyzcal_adjust_pixels(uint8_t* pixels, uint16_t* histo);
|
||||
|
||||
extern int16_t xyzcal_match_pattern_12x12_in_32x32(uint16_t* pattern, uint8_t* pixels, uint8_t x, uint8_t y);
|
||||
|
||||
extern int16_t xyzcal_find_pattern_12x12_in_32x32(uint8_t* pixels, uint16_t* pattern, uint8_t* pc, uint8_t* pr);
|
||||
|
||||
extern int8_t xyzcal_find_point_center2(uint16_t delay_us);
|
||||
|
||||
//extern int8_t xyzcal_find_point_center(int16_t x0, int16_t y0, int16_t z0, int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t turns);
|
||||
|
||||
extern bool xyzcal_searchZ(void);
|
||||
|
||||
extern bool xyzcal_scan_and_process(void);
|
||||
|
324
PF-build.sh
324
PF-build.sh
@ -15,7 +15,7 @@
|
||||
# 3. Install zip with 'apt-get install zip'
|
||||
# 4. Install python3 with 'apt-get install python3'
|
||||
# 5. Add command 'ln -sf /usr/bin/python3.5 /usr/bin/python' to link python3 to python.
|
||||
# Donnot istall 'python' as python 2.x has end of life see https://pythonclock.org/
|
||||
# Do not install 'python' as python 2.x has end of life see https://pythonclock.org/
|
||||
# 6. Add at top of ~/.bashrc following lines by using 'sudo nano ~/.bashrc'
|
||||
#
|
||||
# export OS="Linux"
|
||||
@ -37,7 +37,7 @@
|
||||
# 2. Another great tool to compare your custom mod and stock firmware is WinMerge http://winmerge.org/downloads/?lang=en
|
||||
#
|
||||
# Example for MK3: open git bash and change to your Firmware directory
|
||||
# <username>@<machinename> MINGW64 /<drive>/path
|
||||
# <username>@<machine name> MINGW64 /<drive>/path
|
||||
# bash build.sh 1_75mm_MK3-EINSy10a-E3Dv6full
|
||||
#
|
||||
# Example for MK25: open git bash and change to your directory
|
||||
@ -56,15 +56,15 @@
|
||||
# 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_18
|
||||
# Version: 1.0.6-Build_36
|
||||
# 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
|
||||
# 17 Jan 2019, 3d-gussner, Build_3, Check for OS Windows or Linux and use the right build environment
|
||||
# 10 Feb 2019, ropaha, Pull Request, Select variant from list while using build.sh
|
||||
# 10 Feb 2019, ropaha, change FW_DEV_VERSION automatically depending on FW_VERSION RC/BETA/ALPHA
|
||||
# 10 Feb 2019, 3d-gussner, 1st tests with english only
|
||||
# 10 Feb 2019, ropaha, added compiling of all variants and english only
|
||||
# 10 Feb 2019, 3d-gussner, 1st tests with English only
|
||||
# 10 Feb 2019, ropaha, added compiling of all variants and English only
|
||||
# 10 Feb 2019, 3d-gussner, Set OUTPUT_FOLDER for hex files
|
||||
# 11 Feb 2019, 3d-gussner/ropaha, Minor changes and fixes
|
||||
# 11 Feb 2019, 3d-gussner, Ready for RC
|
||||
@ -80,50 +80,63 @@
|
||||
# Configuration_prusa.h
|
||||
# language build files
|
||||
# multi language firmware files exist and clean them up
|
||||
# 15 Feb 2019, 3d-gussner, Fixed selction GOLD/UNKNOWN DEV_STATUS for ALL variants builds, so you have to choose only once
|
||||
# 15 Feb 2019, 3d-gussner, Fixed selection GOLD/UNKNOWN DEV_STATUS for ALL variants builds, so you have to choose only once
|
||||
# 15 Feb 2019, 3d-gussner, Added some colored output
|
||||
# 15 Feb 2019, 3d-gussner, troubleshooting and minor fixes
|
||||
# 16 Feb 2019, 3d-gussner, Script can be run using arguments
|
||||
# $1 = variant, example "1_75mm_MK3-EINSy10a-E3Dv6full.h" at this moment it is not possible to use ALL
|
||||
# $2 = multi language OR english only [ALL/EN_ONLY]
|
||||
# $2 = multi language OR English only [ALL/EN_ONLY]
|
||||
# $3 = development status [GOLD/RC/BETA/ALPHA/DEVEL/DEBUG]
|
||||
# If one argument is wrong a list of valid one will be shown
|
||||
# 13 Mar 2019, 3d-gussner, MKbel updated the linux build environment to version 1.0.2 with an Fix maximum firmware flash size.
|
||||
# 13 Mar 2019, 3d-gussner, MKbel updated the Linux build environment to version 1.0.2 with an Fix maximum firmware flash size.
|
||||
# So did I
|
||||
# 11 Jul 2019, deliopoulos,Updated to v1.0.6 as Prusa needs a new board definition for Firmware 3.8.x86_64
|
||||
# - Splitted the Download of Windows Arduino IDE 1.8.5 and Prusa specific part
|
||||
# - Split the Download of Windows Arduino IDE 1.8.5 and Prusa specific part
|
||||
# --> less download volume needed and saves some time
|
||||
#
|
||||
# 13 Jul 2019, deliopoulos,Splitting of Ardunio IDE and Prusa parts also for Linux64
|
||||
# 13 Jul 2019, deliopoulos,Splitting of Arduino IDE and Prusa parts also for Linux64
|
||||
# 13 Jul 2019, 3d-gussner, Added Linux 32-bit version (untested yet)
|
||||
# MacOS could be added in future if needs
|
||||
# 14 Jul 2019, 3d-gussner, Update preferences and make it really portable
|
||||
# 15 Jul 2019, 3d-gussner, New PF-build-env gihub branch
|
||||
# 16 Jul 2019, 3d-gussner, New Arduino_boards github fork
|
||||
# 15 Jul 2019, 3d-gussner, New PF-build-env GitHub branch
|
||||
# 16 Jul 2019, 3d-gussner, New Arduino_boards GitHub fork
|
||||
# 17 Jul 2019, 3d-gussner, Final tests under Windows 10 and Linux Subsystem for Windows
|
||||
# 18 Jul 2019, 3d-gussner, Added python check
|
||||
# 18 Jul 2019, deliopoulos, No need more for changing 'platform.txt' file as it comes with the Arduino Boards.
|
||||
# 18 Jul 2019, deliopoulos, Modified 'PF_BUILD_FILE_URL' to use 'BUILD_ENV' variable
|
||||
# 22 Jul 2019, 3d-gussner, Modiffied checks to check folder and/or installation output exists.
|
||||
# 22 Jul 2019, 3d-gussner, Modified checks to check folder and/or installation output exists.
|
||||
# 22 Jul 2019, 3d-gussner, Added check if Arduino IDE 1.8.5 boards have been updated
|
||||
# 22 Jul 2019, 3d-gussner, Changed exit numbers 1-13 for prepare build env 21-28 for prepare compiling 31-36 compiling
|
||||
# 22 Jul 2019, 3d-gussner, Changed BOARD_URL to DRracers respository after he pulled my PR https://github.com/DRracer/Arduino_Boards/pull/1
|
||||
# 22 Jul 2019, 3d-gussner, Changed BOARD_URL to DRracers repository after he pulled my PR https://github.com/DRracer/Arduino_Boards/pull/1
|
||||
# 23 Jul 2019, 3d-gussner, Changed Build-env path to "PF-build-dl" as requested in PR https://github.com/prusa3d/Prusa-Firmware/pull/2028
|
||||
# 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
|
||||
# 23 Sep 2019, 3d-gussner, Prepare PF-build.sh for coming Prusa3d/Arduino_Boards version 1.0.2 Pull Request
|
||||
# 17 Oct 2019, 3d-gussner, Changed folder and check file names to have separated build environments depending on Arduino IDE version and
|
||||
# board-versions.
|
||||
# 15 Dec 2019, 3d-gussner, Prepare for switch to Prusa3d/PF-build-env repository
|
||||
# 15 Dec 2019, 3d-gussner, Fix Audrino user preferences for the chosen board.
|
||||
# 15 Dec 2019, 3d-gussner, Fix Arduino user preferences for the chosen board.
|
||||
# 17 Dec 2019, 3d-gussner, Fix "timer0_fract = 0" warning by using Arduino_boards v1.0.3
|
||||
# 28 Apr 2020, 3d-gussner, Added RC3 detection
|
||||
# 03 May 2020, deliopoulos, Accept all RCx as RC versions
|
||||
# 05 May 2020, 3d-gussner, Make a copy of `not_tran.txt`and `not_used.txt` as `not_tran_$VARIANT.txt`and `not_used_$VARIANT.txt`
|
||||
# After compiling All multilanguage vairants it makes it easier to find missing or unused transltions.
|
||||
# After compiling All multi-language variants it makes it easier to find missing or unused translations.
|
||||
# 12 May 2020, DRracer , Cleanup double MK2/s MK25/s `not_tran` and `not_used` files
|
||||
# 13 May 2020, leptun , If cleanup files do not exist don't try to.
|
||||
# 01 Oct 2020, 3d-gussner, Bug fix if using argument EN_ONLY. Thank to @leptun for pointing out.
|
||||
# Change Build number to script commits 'git rev-list --count HEAD PF-build.sh'
|
||||
# 02 Oct 2020, 3d-gussner, Add UNKNOWN as argument option
|
||||
# 05 Oct 2020, 3d-gussner, Disable pause and warnings using command line with all needed arguments
|
||||
# Install needed apps under linux if needed.
|
||||
# Clean PF-Firmware build when changing git branch
|
||||
# 02 Nov 2020, 3d-gussner, Check for "gawk" on Linux
|
||||
# Add argument to change build number automatically to current commit or define own number
|
||||
# Update exit numbers 1-13 for prepare build env 21-29 for prepare compiling 30-36 compiling
|
||||
# 08 Jan 2021, 3d-gussner, Comment out 'sudo' auto installation
|
||||
# Add '-?' '-h' help option
|
||||
# 27 Jan 2021, 3d-gussner, Add `-c`, `-p` and `-n` options
|
||||
|
||||
#### Start check if OSTYPE is supported
|
||||
OS_FOUND=$( command -v uname)
|
||||
|
||||
@ -198,13 +211,14 @@ if ! type zip > /dev/null; then
|
||||
elif [ $TARGET_OS == "linux" ]; then
|
||||
echo "$(tput setaf 1)Missing 'zip' which is important to run this script"
|
||||
echo "install it with the command $(tput setaf 2)'sudo apt-get install zip'$(tput sgr0)"
|
||||
#sudo apt-get update && apt-get install zip
|
||||
exit 3
|
||||
fi
|
||||
fi
|
||||
# Check python ... needed during language build
|
||||
if ! type python > /dev/null; then
|
||||
if [ $TARGET_OS == "windows" ]; then
|
||||
echo "$(tput setaf 1)Missing 'python' which is important to run this script"
|
||||
echo "$(tput setaf 1)Missing 'python3' which is important to run this script"
|
||||
exit 4
|
||||
elif [ $TARGET_OS == "linux" ]; then
|
||||
echo "$(tput setaf 1)Missing 'python' which is important to run this script"
|
||||
@ -212,6 +226,17 @@ if ! type python > /dev/null; then
|
||||
echo "install it with the command $(tput setaf 2)'sudo apt-get install python3'."
|
||||
echo "Check which version of Python3 has been installed using 'ls /usr/bin/python3*'"
|
||||
echo "Use 'sudo ln -sf /usr/bin/python3.x /usr/bin/python' (where 'x' is your version number) to make it default.$(tput sgr0)"
|
||||
#sudo apt-get update && apt-get install python3 && ln -sf /usr/bin/python3 /usr/bin/python
|
||||
exit 4
|
||||
fi
|
||||
fi
|
||||
|
||||
# Check gawk ... needed during language build
|
||||
if ! type gawk > /dev/null; then
|
||||
if [ $TARGET_OS == "linux" ]; then
|
||||
echo "$(tput setaf 1)Missing 'gawk' which is important to run this script"
|
||||
echo "install it with the command $(tput setaf 2)'sudo apt-get install gawk'."
|
||||
#sudo apt-get update && apt-get install gawk
|
||||
exit 4
|
||||
fi
|
||||
fi
|
||||
@ -241,7 +266,7 @@ echo "Script path :" $SCRIPT_PATH
|
||||
echo "OS :" $OS
|
||||
echo "OS type :" $TARGET_OS
|
||||
echo ""
|
||||
echo "Ardunio IDE :" $ARDUINO_ENV
|
||||
echo "Arduino IDE :" $ARDUINO_ENV
|
||||
echo "Build env :" $BUILD_ENV
|
||||
echo "Board :" $BOARD
|
||||
echo "Package name:" $BOARD_PACKAGE_NAME
|
||||
@ -422,8 +447,73 @@ fi
|
||||
#### Start
|
||||
cd $SCRIPT_PATH
|
||||
|
||||
# First argument defines which variant of the Prusa Firmware will be compiled
|
||||
if [ -z "$1" ] ; then
|
||||
# Check if git is available
|
||||
if type git > /dev/null; then
|
||||
git_available="1"
|
||||
fi
|
||||
|
||||
while getopts v:l:d:b:o:c:p:n:?h flag
|
||||
do
|
||||
case "${flag}" in
|
||||
v) variant_flag=${OPTARG};;
|
||||
l) language_flag=${OPTARG};;
|
||||
d) devel_flag=${OPTARG};;
|
||||
b) build_flag=${OPTARG};;
|
||||
o) output_flag=${OPTARG};;
|
||||
c) clean_flag=${OPTARG};;
|
||||
p) prusa_flag=${OPTARG};;
|
||||
n) new_build_flag=${OPTARG};;
|
||||
?) help_flag=1;;
|
||||
h) help_flag=1;;
|
||||
esac
|
||||
done
|
||||
#echo "variant_flag: $variant_flag";
|
||||
#echo "language_flag: $language_flag";
|
||||
#echo "devel_flag: $devel_flag";
|
||||
#echo "build_flag: $build_flag";
|
||||
#echo "output_flag: $output_flag";
|
||||
#echo "help_flag: $help_flag"
|
||||
#echo "clean_flag: $clean_flag"
|
||||
#echo "prusa_flag: $prusa_flag"
|
||||
#echo "new_build_flag: $new_build_flag"
|
||||
|
||||
#
|
||||
# '?' 'h' argument usage and help
|
||||
if [ "$help_flag" == "1" ] ; then
|
||||
echo "***************************************"
|
||||
echo "* PF-build.sh Version: 1.0.6-Build_33 *"
|
||||
echo "***************************************"
|
||||
echo "Arguments:"
|
||||
echo "$(tput setaf 2)-v$(tput sgr0) Variant '$(tput setaf 2)All$(tput sgr0)' or variant file name"
|
||||
echo "$(tput setaf 2)-l$(tput sgr0) Languages '$(tput setaf 2)ALL$(tput sgr0)' for multi language or '$(tput setaf 2)EN_ONLY$(tput sgr0)' for English only"
|
||||
echo "$(tput setaf 2)-d$(tput sgr0) Devel build '$(tput setaf 2)GOLD$(tput sgr0)', '$(tput setaf 2)RC$(tput sgr0)', '$(tput setaf 2)BETA$(tput sgr0)', '$(tput setaf 2)ALPHA$(tput sgr0)', '$(tput setaf 2)DEBUG$(tput sgr0)', '$(tput setaf 2)DEVEL$(tput sgr0)' and '$(tput setaf 2)UNKNOWN$(tput sgr0)'"
|
||||
echo "$(tput setaf 2)-b$(tput sgr0) Build/commit number '$(tput setaf 2)Auto$(tput sgr0)' needs git or a number"
|
||||
echo "$(tput setaf 2)-o$(tput sgr0) Output '$(tput setaf 2)1$(tput sgr0)' force or '$(tput setaf 2)0$(tput sgr0)' block output and delays"
|
||||
echo "$(tput setaf 2)-c$(tput sgr0) Do not clean up lang build'$(tput setaf 2)0$(tput sgr0)' no '$(tput setaf 2)1$(tput sgr0)' yes"
|
||||
echo "$(tput setaf 2)-p$(tput sgr0) Keep Configuration_prusa.h '$(tput setaf 2)0$(tput sgr0)' no '$(tput setaf 2)1$(tput sgr0)' yes"
|
||||
echo "$(tput setaf 2)-n$(tput sgr0) New fresh build '$(tput setaf 2)0$(tput sgr0)' no '$(tput setaf 2)1$(tput sgr0)' yes"
|
||||
echo "$(tput setaf 2)-?$(tput sgr0) Help"
|
||||
echo "$(tput setaf 2)-h$(tput sgr0) Help"
|
||||
echo
|
||||
echo "Brief USAGE:"
|
||||
echo " $(tput setaf 2)./PF-build.sh$(tput sgr0) [-v] [-l] [-d] [-b] [-o] [-c] [-p] [-n]"
|
||||
echo
|
||||
echo "Example:"
|
||||
echo " $(tput setaf 2)./PF-build.sh -v All -l ALL -d GOLD$(tput sgr0)"
|
||||
echo " Will build all variants as multi language and final GOLD version"
|
||||
echo
|
||||
echo " $(tput setaf 2) ./PF-build.sh -v 1_75mm_MK3S-EINSy10a-E3Dv6full.h -b Auto -l ALL -d GOLD -o 1 -c 1 -p 1 -n 1$(tput sgr0)"
|
||||
echo " Will build MK3S multi language final GOLD firmware "
|
||||
echo " with current commit count number and output extra information,"
|
||||
echo " not delete lang build temporary files, keep Configuration_prusa.h and build with new fresh build folder."
|
||||
echo
|
||||
exit
|
||||
|
||||
fi
|
||||
|
||||
#
|
||||
# '-v' argument defines which variant of the Prusa Firmware will be compiled
|
||||
if [ -z "$variant_flag" ] ; then
|
||||
# Select which variant of the Prusa Firmware will be compiled, like
|
||||
PS3="Select a variant: "
|
||||
while IFS= read -r -d $'\0' f; do
|
||||
@ -443,7 +533,7 @@ if [ -z "$1" ] ; then
|
||||
;;
|
||||
"Quit")
|
||||
echo "You chose to stop"
|
||||
exit
|
||||
exit 20
|
||||
;;
|
||||
*)
|
||||
echo "$(tput setaf 1)This is not a valid variant$(tput sgr0)"
|
||||
@ -451,21 +541,28 @@ if [ -z "$1" ] ; then
|
||||
esac
|
||||
done
|
||||
else
|
||||
if [ -f "$SCRIPT_PATH/Firmware/variants/$1" ] ; then
|
||||
VARIANTS=$1
|
||||
if [ -f "$SCRIPT_PATH/Firmware/variants/$variant_flag" ] ; then
|
||||
VARIANTS=$variant_flag
|
||||
elif [ "$variant_flag" == "All" ] ; then
|
||||
while IFS= read -r -d $'\0' f; do
|
||||
options[i++]="$f"
|
||||
done < <(find Firmware/variants/ -maxdepth 1 -type f -name "*.h" -print0 )
|
||||
VARIANT="All"
|
||||
VARIANTS=${options[*]}
|
||||
else
|
||||
echo "$(tput setaf 1)$1 could not be found in Firmware/variants please choose a valid one$(tput setaf 2)"
|
||||
echo "$(tput setaf 1)Argument $variant_flag could not be found in Firmware/variants please choose a valid one.$(tput sgr0)"
|
||||
echo "Only $(tput setaf 2)'All'$(tput sgr0) and file names below are allowed as variant '-v' argument.$(tput setaf 2)"
|
||||
ls -1 $SCRIPT_PATH/Firmware/variants/*.h | xargs -n1 basename
|
||||
echo "$(tput sgr0)"
|
||||
exit 21
|
||||
fi
|
||||
fi
|
||||
|
||||
#Second argument defines if it is an english only version. Known values EN_ONLY / ALL
|
||||
#'-l' argument defines if it is an English only version. Known values EN_ONLY / ALL
|
||||
#Check default language mode
|
||||
MULTI_LANGUAGE_CHECK=$(grep --max-count=1 "^#define LANG_MODE *" $SCRIPT_PATH/Firmware/config.h|sed -e's/ */ /g'|cut -d ' ' -f3)
|
||||
|
||||
if [ -z "$2" ] ; then
|
||||
if [ -z "$language_flag" ] ; then
|
||||
PS3="Select a language: "
|
||||
echo
|
||||
echo "Which lang-build do you want?"
|
||||
@ -473,12 +570,10 @@ if [ -z "$2" ] ; then
|
||||
case $yn in
|
||||
"Multi languages")
|
||||
LANGUAGES="ALL"
|
||||
sed -i -- "s/^#define LANG_MODE *0/#define LANG_MODE 1/g" $SCRIPT_PATH/Firmware/config.h
|
||||
break
|
||||
;;
|
||||
"English only")
|
||||
LANGUAGES="EN_ONLY"
|
||||
sed -i -- "s/^#define LANG_MODE *1/#define LANG_MODE 0/g" $SCRIPT_PATH/Firmware/config.h
|
||||
break
|
||||
;;
|
||||
*)
|
||||
@ -487,47 +582,106 @@ if [ -z "$2" ] ; then
|
||||
esac
|
||||
done
|
||||
else
|
||||
if [[ "$2" == "ALL" || "$2" == "EN_ONLY" ]] ; then
|
||||
LANGUAGES=$2
|
||||
if [[ "$language_flag" == "ALL" || "$language_flag" == "EN_ONLY" ]] ; then
|
||||
LANGUAGES=$language_flag
|
||||
else
|
||||
echo "$(tput setaf 1)Language argument is wrong!$(tput sgr0)"
|
||||
echo "Only $(tput setaf 2)'ALL'$(tput sgr0) or $(tput setaf 2)'EN_ONLY'$(tput sgr0) are allowed as 2nd argument!"
|
||||
echo "Only $(tput setaf 2)'ALL'$(tput sgr0) or $(tput setaf 2)'EN_ONLY'$(tput sgr0) are allowed as language '-l' argument!"
|
||||
exit 22
|
||||
fi
|
||||
fi
|
||||
#Check if DEV_STATUS is selected via argument 3
|
||||
if [ ! -z "$3" ] ; then
|
||||
if [[ "$3" == "GOLD" || "$3" == "RC" || "$3" == "BETA" || "$3" == "ALPHA" || "$3" == "DEVEL" || "$3" == "DEBUG" ]] ; then
|
||||
DEV_STATUS_SELECTED=$3
|
||||
#Check if DEV_STATUS is selected via argument '-d'
|
||||
if [ ! -z "$devel_flag" ] ; then
|
||||
if [[ "$devel_flag" == "GOLD" || "$devel_flag" == "RC" || "$devel_flag" == "BETA" || "$devel_flag" == "ALPHA" || "$devel_flag" == "DEVEL" || "$devel_flag" == "DEBUG" || "$devel_flag" == "UNKNOWN" ]] ; then
|
||||
DEV_STATUS_SELECTED=$devel_flag
|
||||
else
|
||||
echo "$(tput setaf 1)Development argument is wrong!$(tput sgr0)"
|
||||
echo "Only $(tput setaf 2)'GOLD', 'RC', 'BETA', 'ALPHA', 'DEVEL' or 'DEBUG'$(tput sgr0) are allowed as 3rd argument!$(tput sgr0)"
|
||||
echo "Only $(tput setaf 2)'GOLD', 'RC', 'BETA', 'ALPHA', 'DEVEL', 'DEBUG' or 'UNKNOWN' $(tput sgr0) are allowed as devel '-d' argument!$(tput sgr0)"
|
||||
exit 23
|
||||
fi
|
||||
fi
|
||||
|
||||
#Check if Build is selected via argument '-b'
|
||||
if [ ! -z "$build_flag" ] ; then
|
||||
if [[ "$build_flag" == "Auto" && "$git_available" == "1" ]] ; then
|
||||
echo "Build changed to $build_flag"
|
||||
BUILD=$(git rev-list --count HEAD)
|
||||
elif [[ $build_flag =~ ^[0-9]+$ ]] ; then
|
||||
BUILD=$build_flag
|
||||
else
|
||||
echo "$(tput setaf 1)Build number argument is wrong!$(tput sgr0)"
|
||||
echo "Only $(tput setaf 2)'Auto' (git needed) or numbers $(tput sgr0) are allowed as build '-b' argument!$(tput sgr0)"
|
||||
exit 24
|
||||
|
||||
fi
|
||||
echo "New Build number is: $BUILD"
|
||||
fi
|
||||
|
||||
# check if script has been started with arguments
|
||||
if [[ "$#" -eq "0" || "$output_flag" == 1 ]] ; then
|
||||
OUTPUT=1
|
||||
else
|
||||
OUTPUT=0
|
||||
fi
|
||||
#echo "Output is:" $OUTPUT
|
||||
|
||||
#Check git branch has changed
|
||||
if [ ! -z "git_available" ]; then
|
||||
BRANCH=""
|
||||
CLEAN_PF_FW_BUILD=0
|
||||
else
|
||||
BRANCH=$(git branch --show-current)
|
||||
echo "Current branch is:" $BRANCH
|
||||
if [ ! -f "$SCRIPT_PATH/../PF-build.branch" ]; then
|
||||
echo "$BRANCH" >| $SCRIPT_PATH/../PF-build.branch
|
||||
echo "created PF-build.branch file"
|
||||
else
|
||||
PRE_BRANCH=$(cat "$SCRIPT_PATH/../PF-build.branch")
|
||||
echo "Previous branch was:" $PRE_BRANCH
|
||||
if [ ! "$BRANCH" == "$PRE_BRANCH" ] ; then
|
||||
CLEAN_PF_FW_BUILD=1
|
||||
echo "$BRANCH" >| $SCRIPT_PATH/../PF-build.branch
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#Set BUILD_ENV_PATH
|
||||
cd ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 24
|
||||
cd ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 25
|
||||
BUILD_ENV_PATH="$( pwd -P )"
|
||||
|
||||
cd ../..
|
||||
|
||||
#Checkif BUILD_PATH exists and if not creates it
|
||||
if [ ! -d "Prusa-Firmware-build" ]; then
|
||||
mkdir Prusa-Firmware-build || exit 25
|
||||
mkdir Prusa-Firmware-build || exit 26
|
||||
fi
|
||||
|
||||
#Set the BUILD_PATH for Arduino IDE
|
||||
cd Prusa-Firmware-build || exit 26
|
||||
cd Prusa-Firmware-build || exit 27
|
||||
BUILD_PATH="$( pwd -P )"
|
||||
|
||||
#Check git branch has changed
|
||||
if [ "$CLEAN_PF_FW_BUILD" == "1" ]; then
|
||||
read -t 10 -p "Branch changed, cleaning Prusa-Firmware-build folder"
|
||||
rm -r *
|
||||
else
|
||||
echo "Nothing to clean up"
|
||||
fi
|
||||
|
||||
for v in ${VARIANTS[*]}
|
||||
do
|
||||
VARIANT=$(basename "$v" ".h")
|
||||
# Find firmware version in Configuration.h file and use it to generate the hex filename
|
||||
FW=$(grep --max-count=1 "\bFW_VERSION\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/ */ /g'|cut -d '"' -f2|sed 's/\.//g')
|
||||
# Find build version in Configuration.h file and use it to generate the hex filename
|
||||
BUILD=$(grep --max-count=1 "\bFW_COMMIT_NR\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/ */ /g'|cut -d ' ' -f3)
|
||||
if [ -z "$BUILD" ] ; then
|
||||
# Find build version in Configuration.h file and use it to generate the hex filename
|
||||
BUILD=$(grep --max-count=1 "\bFW_COMMIT_NR\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/ */ /g'|cut -d ' ' -f3)
|
||||
else
|
||||
# Find and replace build version in Configuration.h file
|
||||
BUILD_ORG=$(grep --max-count=1 "\bFW_COMMIT_NR\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/ */ /g'|cut -d ' ' -f3)
|
||||
echo "Original build number: $BUILD_ORG"
|
||||
sed -i -- "s/^#define FW_COMMIT_NR.*/#define FW_COMMIT_NR $BUILD/g" $SCRIPT_PATH/Firmware/Configuration.h
|
||||
fi
|
||||
# Check if the motherboard is an EINSY and if so only one hex file will generated
|
||||
MOTHERBOARD=$(grep --max-count=1 "\bMOTHERBOARD\b" $SCRIPT_PATH/Firmware/variants/$VARIANT.h | sed -e's/ */ /g' |cut -d ' ' -f3)
|
||||
# Check development status
|
||||
@ -571,7 +725,7 @@ do
|
||||
fi
|
||||
#Prepare hex files folders
|
||||
if [ ! -d "$SCRIPT_PATH/../PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD" ]; then
|
||||
mkdir -p $SCRIPT_PATH/../PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD || exit 27
|
||||
mkdir -p $SCRIPT_PATH/../PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD || exit 28
|
||||
fi
|
||||
OUTPUT_FOLDER="PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD"
|
||||
|
||||
@ -580,18 +734,24 @@ do
|
||||
echo ""
|
||||
ls -1 $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT.hex | xargs -n1 basename
|
||||
echo "$(tput setaf 6)This hex file to be compiled already exists! To cancel this process press CRTL+C and rename existing hex file.$(tput sgr 0)"
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
fi
|
||||
elif [[ -f "$SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT-EN_ONLY.hex" && "$LANGUAGES" == "EN_ONLY" ]]; then
|
||||
echo ""
|
||||
ls -1 $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT-EN_ONLY.hex | xargs -n1 basename
|
||||
echo "$(tput setaf 6)This hex file to be compiled already exists! To cancel this process press CRTL+C and rename existing hex file.$(tput sgr 0)"
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
fi
|
||||
fi
|
||||
if [[ -f "$SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT.zip" && "$LANGUAGES" == "ALL" ]]; then
|
||||
echo ""
|
||||
ls -1 $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT.zip | xargs -n1 basename
|
||||
echo "$(tput setaf 6)This zip file to be compiled already exists! To cancel this process press CRTL+C and rename existing hex file.$(tput sgr 0)"
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
fi
|
||||
fi
|
||||
|
||||
#List some useful data
|
||||
@ -608,11 +768,13 @@ do
|
||||
|
||||
#Prepare Firmware to be compiled by copying variant as Configuration_prusa.h
|
||||
if [ ! -f "$SCRIPT_PATH/Firmware/Configuration_prusa.h" ]; then
|
||||
cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 28
|
||||
cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 29
|
||||
else
|
||||
echo "$(tput setaf 6)Configuration_prusa.h already exist it will be overwritten in 10 seconds by the chosen variant.$(tput sgr 0)"
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 28
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
fi
|
||||
cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 29
|
||||
fi
|
||||
|
||||
#Prepare Configuration.h to use the correct FW_DEV_VERSION to prevent LCD messages when connecting with OctoPrint
|
||||
@ -621,14 +783,16 @@ do
|
||||
# set FW_REPOSITORY
|
||||
sed -i -- 's/#define FW_REPOSITORY "Unknown"/#define FW_REPOSITORY "Prusa3d"/g' $SCRIPT_PATH/Firmware/Configuration.h
|
||||
|
||||
#Prepare english only or multilanguage version to be build
|
||||
if [ $LANGUAGES == "ALL" ]; then
|
||||
#Prepare English only or multi-language version to be build
|
||||
if [ $LANGUAGES == "EN_ONLY" ]; then
|
||||
echo " "
|
||||
echo "Multi-language firmware will be built"
|
||||
echo "English only language firmware will be built"
|
||||
sed -i -- "s/^#define LANG_MODE *1/#define LANG_MODE 0/g" $SCRIPT_PATH/Firmware/config.h
|
||||
echo " "
|
||||
else
|
||||
echo " "
|
||||
echo "English only language firmware will be built"
|
||||
echo "Multi-language firmware will be built"
|
||||
sed -i -- "s/^#define LANG_MODE *0/#define LANG_MODE 1/g" $SCRIPT_PATH/Firmware/config.h
|
||||
echo " "
|
||||
fi
|
||||
|
||||
@ -651,9 +815,17 @@ do
|
||||
|
||||
echo "Start to build Prusa Firmware ..."
|
||||
echo "Using variant $VARIANT$(tput setaf 3)"
|
||||
sleep 2
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
sleep 2
|
||||
fi
|
||||
|
||||
#New fresh PF-Firmware-build
|
||||
if [ "$new_build_flag" == "1" ]; then
|
||||
rm -r -f $BUILD_PATH/* || exit 36
|
||||
fi
|
||||
|
||||
#$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
|
||||
$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 30
|
||||
echo "$(tput sgr 0)"
|
||||
|
||||
if [ $LANGUAGES == "ALL" ]; then
|
||||
@ -661,7 +833,9 @@ do
|
||||
|
||||
echo "Building multi language firmware" $MULTI_LANGUAGE_CHECK
|
||||
echo "$(tput sgr 0)"
|
||||
sleep 2
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
sleep 2
|
||||
fi
|
||||
cd $SCRIPT_PATH/lang
|
||||
echo "$(tput setaf 3)"
|
||||
./config.sh || exit 31
|
||||
@ -670,7 +844,9 @@ do
|
||||
if [ -f "lang_en.tmp" ]; then
|
||||
echo ""
|
||||
echo "$(tput setaf 6)Previous lang build files already exist these will be cleaned up in 10 seconds.$(tput sgr 0)"
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
fi
|
||||
echo "$(tput setaf 3)"
|
||||
./lang-clean.sh
|
||||
echo "$(tput sgr 0)"
|
||||
@ -678,7 +854,9 @@ do
|
||||
if [ -f "progmem.out" ]; then
|
||||
echo ""
|
||||
echo "$(tput setaf 6)Previous firmware build files already exist these will be cleaned up in 10 seconds.$(tput sgr 0)"
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
read -t 10 -p "Press Enter to continue..."
|
||||
fi
|
||||
echo "$(tput setaf 3)"
|
||||
./fw-clean.sh
|
||||
echo "$(tput sgr 0)"
|
||||
@ -713,17 +891,21 @@ do
|
||||
fi
|
||||
fi
|
||||
# Cleanup after build
|
||||
echo "$(tput setaf 3)"
|
||||
./fw-clean.sh || exit 34
|
||||
./lang-clean.sh || exit 35
|
||||
echo "$(tput sgr 0)"
|
||||
if [[ -z "$clean_flag" || "$clean_flag" == "0" ]]; then
|
||||
echo "$(tput setaf 3)"
|
||||
./fw-clean.sh || exit 34
|
||||
./lang-clean.sh || exit 35
|
||||
echo "$(tput sgr 0)"
|
||||
fi
|
||||
else
|
||||
echo "$(tput setaf 2)Copying English only firmware to PF-build-hex folder$(tput sgr 0)"
|
||||
cp -f $BUILD_PATH/Firmware.ino.hex $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT-EN_ONLY.hex || exit 34
|
||||
fi
|
||||
|
||||
# Cleanup Firmware
|
||||
rm $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 36
|
||||
if [[ -z "$prusa_flag" || "$prusa_flag" == "0" ]]; then
|
||||
rm $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 36
|
||||
fi
|
||||
if find $SCRIPT_PATH/lang/ -name '*RAMBo10a*.txt' -printf 1 -quit | grep -q 1
|
||||
then
|
||||
rm $SCRIPT_PATH/lang/*RAMBo10a*.txt
|
||||
@ -740,13 +922,25 @@ do
|
||||
then
|
||||
rm $SCRIPT_PATH/lang/not_used.txt
|
||||
fi
|
||||
|
||||
#New fresh PF-Firmware-build
|
||||
if [ "$new_build_flag" == "1" ]; then
|
||||
rm -r -f $BUILD_PATH/* || exit 36
|
||||
fi
|
||||
|
||||
# Restore files to previous state
|
||||
sed -i -- "s/^#define FW_DEV_VERSION FW_VERSION_$DEV_STATUS/#define FW_DEV_VERSION FW_VERSION_UNKNOWN/g" $SCRIPT_PATH/Firmware/Configuration.h
|
||||
sed -i -- 's/^#define FW_REPOSITORY "Prusa3d"/#define FW_REPOSITORY "Unknown"/g' $SCRIPT_PATH/Firmware/Configuration.h
|
||||
if [ ! -z "$BUILD_ORG" ] ; then
|
||||
sed -i -- "s/^#define FW_COMMIT_NR.*/#define FW_COMMIT_NR $BUILD_ORG/g" $SCRIPT_PATH/Firmware/Configuration.h
|
||||
fi
|
||||
echo $MULTI_LANGUAGE_CHECK
|
||||
#sed -i -- "s/^#define LANG_MODE * /#define LANG_MODE $MULTI_LANGUAGE_CHECK/g" $SCRIPT_PATH/Firmware/config.h
|
||||
sed -i -- "s/^#define LANG_MODE *1/#define LANG_MODE ${MULTI_LANGUAGE_CHECK}/g" $SCRIPT_PATH/Firmware/config.h
|
||||
sed -i -- "s/^#define LANG_MODE *0/#define LANG_MODE ${MULTI_LANGUAGE_CHECK}/g" $SCRIPT_PATH/Firmware/config.h
|
||||
sleep 5
|
||||
if [ $OUTPUT == "1" ] ; then
|
||||
sleep 5
|
||||
fi
|
||||
done
|
||||
|
||||
# Switch to hex path and list build files
|
||||
|
25
README.md
25
README.md
@ -73,7 +73,7 @@ _Note: Multi language build is not supported._
|
||||
|
||||
**c.** Modify compiler flags in `platform.txt` file
|
||||
|
||||
* The platform.txt file can be found in Arduino instalation directory, or after Arduino has been updated at: `"C:\Users\(user)\AppData\Local\Arduino15\packages\arduino\hardware\avr\(version)"` If you can locate the file in both places, file from user profile is probably used.
|
||||
* The platform.txt file can be found in Arduino installation directory, or after Arduino has been updated at: `"C:\Users\(user)\AppData\Local\Arduino15\packages\arduino\hardware\avr\(version)"` If you can locate the file in both places, file from user profile is probably used.
|
||||
|
||||
* Add `"-Wl,-u,vfprintf -lprintf_flt -lm"` to `"compiler.c.elf.flags="` before existing flag "-Wl,--gc-sections"
|
||||
|
||||
@ -111,10 +111,13 @@ _notes: Script and instructions contributed by 3d-gussner. Use at your own risk.
|
||||
- follow the Microsoft guide https://docs.microsoft.com/en-us/windows/wsl/install-win10
|
||||
You can also use the 'prepare_winbuild.ps1' powershell script with Administrator rights
|
||||
- Tested versions are at this moment
|
||||
- Ubuntu other may different
|
||||
- Ubuntu and Debian, other may different
|
||||
- After the installation and reboot please open your Ubuntu bash and do following steps
|
||||
- run command `apt-get update`
|
||||
- to install zip run `apt-get install zip`
|
||||
- run command `sudo apt-get update`
|
||||
- run command `sudo apt-get upgrade`
|
||||
- to install zip run `sudo apt-get install zip`
|
||||
- to install dos2unix run `sudo apt-get install dos2unix`
|
||||
- run `dos2unix PF-build.sh` to convert the windows line endings to unix line endings
|
||||
- add few lines at the top of `~/.bashrc` by running `sudo nano ~/.bashrc`
|
||||
|
||||
export OS="Linux"
|
||||
@ -122,11 +125,11 @@ _notes: Script and instructions contributed by 3d-gussner. Use at your own risk.
|
||||
export GPG_TTY=$(tty)
|
||||
|
||||
use `CRTL-X` to close nano and confirm to write the new entries
|
||||
- restart Ubuntu bash
|
||||
Now your Ubuntu subsystem is ready to use the automatic `PF-build.sh` script and compile your firmware correctly
|
||||
- restart Ubuntu/Debian bash
|
||||
- Now your Ubuntu/Debian subsystem is ready to use the automatic `PF-build.sh` script and compile your firmware correctly
|
||||
|
||||
#### Some Tips for Ubuntu
|
||||
- Linux is case sensetive so please don't forget to use capital letters where needed, like changing to a directory
|
||||
#### Some Tips for Ubuntu and Debian
|
||||
- Linux is case sensitive so please don't forget to use capital letters where needed, like changing to a directory
|
||||
- To change the path to your Prusa-Firmware location you downloaded and unzipped
|
||||
- Example: You files are under `C:\Users\<your-username>\Downloads\Prusa-Firmware-MK3`
|
||||
- use under Ubuntu the following command `cd /mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3`
|
||||
@ -137,7 +140,7 @@ Now your Ubuntu subsystem is ready to use the automatic `PF-build.sh` script and
|
||||
- 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
|
||||
#### Compile Prusa-firmware with Ubuntu/Debian Linux subsystem installed
|
||||
- open Ubuntu bash
|
||||
- change to your source code folder (case sensitive)
|
||||
- run `./PF-build.sh`
|
||||
@ -206,7 +209,7 @@ or visit https://prusa3d.github.io/Prusa-Firmware-Doc for doxygen generated outp
|
||||
# 5. FAQ
|
||||
Q:I built firmware using Arduino and I see "?" instead of numbers in printer user interface.
|
||||
|
||||
A:Step 1.c was ommited or you updated Arduino and now platform.txt located somewhere in your user profile is used.
|
||||
A:Step 1.c was omitted or you updated Arduino and now platform.txt located somewhere in your user profile is used.
|
||||
|
||||
Q:I built firmware using Arduino and printer now speaks Klingon (nonsense characters and symbols are displayed @^#$&*°;~ÿ)
|
||||
|
||||
@ -218,4 +221,4 @@ A:Our production builds are 99.9% equivalent to https://github.com/prusa3d/Prusa
|
||||
|
||||
Q:Why are build instructions for Arduino mess.
|
||||
|
||||
Y:We are too lazy to ship proper board definition for Arduino. We plan to swich to cmake + ninja to be inherently multiplatform, easily integrate build tools, suport more IDEs, get 10 times shorter build times and be able to update compiler whenewer we want.
|
||||
Y:We are too lazy to ship proper board definition for Arduino. We plan to switch to cmake + ninja to be inherently multiplatform, easily integrate build tools, suport more IDEs, get 10 times shorter build times and be able to update compiler whenever we want.
|
||||
|
@ -5,7 +5,7 @@
|
||||
#
|
||||
# Input files:
|
||||
# lang_en.txt or lang_en_xx.txt
|
||||
#
|
||||
#
|
||||
# Output files:
|
||||
# lang_xx.bin
|
||||
#
|
||||
@ -82,7 +82,7 @@ generate_binary()
|
||||
rm -f lang_$1.dat
|
||||
LNG=$1
|
||||
#check lang dictionary
|
||||
/usr/bin/env python lang-check.py $1 --no-warning
|
||||
./lang-check.py $1 --no-warning
|
||||
#create lang_xx.tmp - different processing for 'en' language
|
||||
if [ "$1" = "en" ]; then
|
||||
#remove comments and empty lines
|
||||
|
0
lang/lang-check.py
Normal file → Executable file
0
lang/lang-check.py
Normal file → Executable file
76
lang/lang_en.txt
Executable file → Normal file
76
lang/lang_en.txt
Executable file → Normal file
@ -1,12 +1,21 @@
|
||||
#
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
|
||||
#MSG_03_OR_OLDER c=18
|
||||
#MSG_IR_03_OR_OLDER c=18
|
||||
" 0.3 or older"
|
||||
|
||||
#MSG_04_OR_NEWER c=18
|
||||
# c=18
|
||||
"FS v0.3 or older"
|
||||
|
||||
#MSG_IR_04_OR_NEWER c=18
|
||||
" 0.4 or newer"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
|
||||
#MSG_IR_UNKNOWN c=18
|
||||
"unknown state"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
|
||||
@ -94,7 +103,7 @@
|
||||
#MSG_BED
|
||||
"Bed"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=18
|
||||
#MSG_BELT_STATUS c=18
|
||||
"Belt status"
|
||||
|
||||
#MSG_RECOVER_PRINT c=20 r=2
|
||||
@ -154,7 +163,7 @@
|
||||
#
|
||||
"Crash detected. Resume print?"
|
||||
|
||||
#
|
||||
#MSG_CRASH c=7
|
||||
"Crash"
|
||||
|
||||
#MSG_CURRENT c=19 r=1
|
||||
@ -178,7 +187,7 @@
|
||||
#MSG_EXTRUDER_CORRECTION c=13
|
||||
"E-correct:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
#MSG_EJECT_FILAMENT c=16
|
||||
"Eject filament"
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
@ -220,7 +229,7 @@
|
||||
#MSG_INFO_EXTRUDER c=18
|
||||
"Extruder info"
|
||||
|
||||
#MSG_MOVE_E
|
||||
#MSG_EXTRUDER c=17
|
||||
"Extruder"
|
||||
|
||||
#
|
||||
@ -238,14 +247,14 @@
|
||||
#MSG_SELFTEST_FAN c=20
|
||||
"Fan test"
|
||||
|
||||
#MSG_FANS_CHECK
|
||||
#MSG_FANS_CHECK c=13
|
||||
"Fans check"
|
||||
|
||||
#MSG_FSENSOR
|
||||
"Fil. sensor"
|
||||
|
||||
# c=14
|
||||
"Filam. runouts"
|
||||
#MSG_FIL_RUNOUTS c=14
|
||||
"Fil. runouts "
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
@ -265,9 +274,6 @@
|
||||
#MSG_FS_ACTION c=10
|
||||
"FS Action"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
|
||||
#MSG_FILE_INCOMPLETE c=20 r=3
|
||||
"File incomplete. Continue anyway?"
|
||||
|
||||
@ -337,14 +343,14 @@
|
||||
#MSG_SELFTEST_CHECK_FSENSOR c=20
|
||||
"Checking sensors "
|
||||
|
||||
#MSG_SELFTEST_CHECK_X c=20
|
||||
"Checking X axis "
|
||||
#MSG_CHECKING_X c=20
|
||||
"Checking X axis"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Y c=20
|
||||
"Checking Y axis "
|
||||
#MSG_CHECKING_Y c=20
|
||||
"Checking Y axis"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Z c=20
|
||||
"Checking Z axis "
|
||||
"Checking Z axis"
|
||||
|
||||
#MSG_CHOOSE_EXTRUDER c=20 r=1
|
||||
"Choose extruder:"
|
||||
@ -367,19 +373,19 @@
|
||||
#MSG_INSERT_FILAMENT c=20
|
||||
"Insert filament"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
#MSG_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
|
||||
#MSG_STEEL_SHEET_CHECK c=20 r=2
|
||||
"Is steel sheet on heatbed?"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT_FAILURES c=20
|
||||
"Last print failures"
|
||||
|
||||
#
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT c=18
|
||||
"Last print"
|
||||
|
||||
#MSG_SELFTEST_EXTRUDER_FAN c=20
|
||||
@ -430,7 +436,7 @@
|
||||
#MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60
|
||||
"Measuring reference height of calibration point"
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
#MSG_MESH_BED_LEVELING c=18
|
||||
"Mesh Bed Leveling"
|
||||
|
||||
#MSG_MMU_OK_RESUMING_POSITION c=20 r=4
|
||||
@ -442,13 +448,13 @@
|
||||
#
|
||||
"Measured skew"
|
||||
|
||||
#
|
||||
#MSG_MMU_FAILS c=14
|
||||
"MMU fails"
|
||||
|
||||
#
|
||||
"MMU load failed "
|
||||
|
||||
#
|
||||
#MSG_MMU_LOAD_FAILS c=14
|
||||
"MMU load fails"
|
||||
|
||||
#MSG_MMU_OK_RESUMING c=20 r=4
|
||||
@ -619,7 +625,7 @@
|
||||
#MSG_FS_PAUSE c=5
|
||||
"Pause"
|
||||
|
||||
#
|
||||
#MSG_POWER_FAILURES c=14
|
||||
"Power failures"
|
||||
|
||||
#MSG_PRINT_ABORTED c=20
|
||||
@ -670,6 +676,9 @@
|
||||
# c=20 r=4
|
||||
"Please unload the filament first, then repeat this action."
|
||||
|
||||
# c=20 r=4
|
||||
"Please check the IR sensor connection, unload filament if present."
|
||||
|
||||
#MSG_RECOVERING_PRINT c=20
|
||||
"Recovering print "
|
||||
|
||||
@ -682,10 +691,10 @@
|
||||
#MSG_CALIBRATE_BED_RESET
|
||||
"Reset XYZ calibr."
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
#MSG_RESET c=14
|
||||
"Reset"
|
||||
|
||||
#MSG_RESUME_PRINT
|
||||
#MSG_RESUME_PRINT c=18
|
||||
"Resume print"
|
||||
|
||||
#MSG_RESUMING_PRINT c=20
|
||||
@ -862,7 +871,7 @@
|
||||
#
|
||||
"Unload"
|
||||
|
||||
#
|
||||
#MSG_TOTAL_FAILURES c=20
|
||||
"Total failures"
|
||||
|
||||
#
|
||||
@ -877,7 +886,7 @@
|
||||
#MSG_UNLOADING_FILAMENT c=20 r=1
|
||||
"Unloading filament"
|
||||
|
||||
#
|
||||
#MSG_TOTAL c=6
|
||||
"Total"
|
||||
|
||||
#MSG_USED c=19 r=1
|
||||
@ -1003,7 +1012,7 @@
|
||||
#MSG_WARN
|
||||
"Warn"
|
||||
|
||||
#
|
||||
#MSG_HW_SETUP c=18
|
||||
"HW Setup"
|
||||
|
||||
#
|
||||
@ -1015,9 +1024,6 @@
|
||||
#MSG_MESH
|
||||
"Mesh"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
|
||||
@ -1039,10 +1045,10 @@
|
||||
#
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
|
||||
#
|
||||
@ -1084,7 +1090,7 @@
|
||||
#MSG_SOUND_BLIND
|
||||
"Assist"
|
||||
|
||||
# c=18
|
||||
#MSG_STEEL_SHEET c=18
|
||||
"Steel sheets"
|
||||
|
||||
#MSG_Z_CORRECTION c=13
|
||||
|
84
lang/lang_en_cz.txt
Executable file → Normal file
84
lang/lang_en_cz.txt
Executable file → Normal file
@ -2,14 +2,26 @@
|
||||
"[%.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_03_OR_OLDER c=18
|
||||
#MSG_IR_03_OR_OLDER c=18
|
||||
" 0.3 or older"
|
||||
" 0.3 nebo starsi"
|
||||
|
||||
#MSG_04_OR_NEWER c=18
|
||||
# c=18
|
||||
"FS v0.3 or older"
|
||||
"FS 0.3 nebo starsi"
|
||||
|
||||
#MSG_IR_04_OR_NEWER c=18
|
||||
" 0.4 or newer"
|
||||
" 0.4 nebo novejsi"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS 0.4 a novejsi"
|
||||
|
||||
#MSG_IR_UNKNOWN c=18
|
||||
"unknown state"
|
||||
"neznamy stav"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" z 4"
|
||||
@ -126,7 +138,7 @@
|
||||
"Bed"
|
||||
"Podlozka"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=18
|
||||
#MSG_BELT_STATUS c=18
|
||||
"Belt status"
|
||||
"Stav remenu"
|
||||
|
||||
@ -206,7 +218,7 @@
|
||||
"Crash detected. Resume print?"
|
||||
"Detekovan naraz. Obnovit tisk?"
|
||||
|
||||
#
|
||||
#MSG_CRASH c=7
|
||||
"Crash"
|
||||
"Naraz"
|
||||
|
||||
@ -238,9 +250,9 @@
|
||||
"E-correct:"
|
||||
"Korekce E:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
#MSG_EJECT_FILAMENT c=16
|
||||
"Eject filament"
|
||||
"Vysunout filament"
|
||||
"Vysunout fil."
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
@ -294,7 +306,7 @@
|
||||
"Extruder info"
|
||||
"\x00"
|
||||
|
||||
#MSG_MOVE_E
|
||||
#MSG_EXTRUDER c=17
|
||||
"Extruder"
|
||||
"\x00"
|
||||
|
||||
@ -318,7 +330,7 @@
|
||||
"Fan test"
|
||||
"Test ventilatoru"
|
||||
|
||||
#MSG_FANS_CHECK
|
||||
#MSG_FANS_CHECK c=13
|
||||
"Fans check"
|
||||
"Kontr. vent."
|
||||
|
||||
@ -326,8 +338,8 @@
|
||||
"Fil. sensor"
|
||||
"Fil. senzor"
|
||||
|
||||
# c=14
|
||||
"Filam. runouts"
|
||||
#MSG_FIL_RUNOUTS c=14
|
||||
"Fil. runouts "
|
||||
"Vypadky filam."
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
@ -354,10 +366,6 @@
|
||||
"FS Action"
|
||||
"FS reakce"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS v0.4 a novejsi"
|
||||
|
||||
#MSG_FILE_INCOMPLETE c=20 r=3
|
||||
"File incomplete. Continue anyway?"
|
||||
"Soubor nekompletni. Pokracovat?"
|
||||
@ -450,16 +458,16 @@
|
||||
"Checking sensors "
|
||||
"Kontrola senzoru"
|
||||
|
||||
#MSG_SELFTEST_CHECK_X c=20
|
||||
"Checking X axis "
|
||||
#MSG_CHECKING_X c=20
|
||||
"Checking X axis"
|
||||
"Kontrola osy X"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Y c=20
|
||||
"Checking Y axis "
|
||||
#MSG_CHECKING_Y c=20
|
||||
"Checking Y axis"
|
||||
"Kontrola osy Y"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Z c=20
|
||||
"Checking Z axis "
|
||||
"Checking Z axis"
|
||||
"Kontrola osy Z"
|
||||
|
||||
#MSG_CHOOSE_EXTRUDER c=20 r=1
|
||||
@ -490,7 +498,7 @@
|
||||
"Insert filament"
|
||||
"Vlozte filament"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
#MSG_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
"Je filament zaveden?"
|
||||
|
||||
@ -498,7 +506,7 @@
|
||||
"Is steel sheet on heatbed?"
|
||||
"Je tiskovy plat na podlozce?"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT_FAILURES c=20
|
||||
"Last print failures"
|
||||
"Selhani posl. tisku"
|
||||
|
||||
@ -506,7 +514,7 @@
|
||||
"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"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT c=18
|
||||
"Last print"
|
||||
"Posledni tisk"
|
||||
|
||||
@ -574,7 +582,7 @@
|
||||
"Measuring reference height of calibration point"
|
||||
"Merim referencni vysku kalibracniho bodu"
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
#MSG_MESH_BED_LEVELING c=18
|
||||
"Mesh Bed Leveling"
|
||||
"\x00"
|
||||
|
||||
@ -590,7 +598,7 @@
|
||||
"Measured skew"
|
||||
"Merene zkoseni"
|
||||
|
||||
#
|
||||
#MSG_MMU_FAILS c=14
|
||||
"MMU fails"
|
||||
"Selhani MMU"
|
||||
|
||||
@ -598,7 +606,7 @@
|
||||
"MMU load failed "
|
||||
"Zavedeni MMU selhalo"
|
||||
|
||||
#
|
||||
#MSG_MMU_LOAD_FAILS c=14
|
||||
"MMU load fails"
|
||||
"MMU selhani zavadeni"
|
||||
|
||||
@ -826,7 +834,7 @@
|
||||
"Pause"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
#MSG_POWER_FAILURES c=14
|
||||
"Power failures"
|
||||
"Vypadky proudu"
|
||||
|
||||
@ -894,6 +902,10 @@
|
||||
"Please unload the filament first, then repeat this action."
|
||||
"Prosim vyjmete filament a zopakujte tuto akci"
|
||||
|
||||
# c=20 r=4
|
||||
"Please check the IR sensor connection, unload filament if present."
|
||||
"Prosim zkontrolujte zapojeni IR senzoru a vyjmuty filament"
|
||||
|
||||
#MSG_RECOVERING_PRINT c=20
|
||||
"Recovering print "
|
||||
"Obnovovani tisku "
|
||||
@ -910,11 +922,11 @@
|
||||
"Reset XYZ calibr."
|
||||
"Reset XYZ kalibr."
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
#MSG_RESET c=14
|
||||
"Reset"
|
||||
"\x00"
|
||||
|
||||
#MSG_RESUME_PRINT
|
||||
#MSG_RESUME_PRINT c=18
|
||||
"Resume print"
|
||||
"Pokracovat"
|
||||
|
||||
@ -1150,7 +1162,7 @@
|
||||
"Unload"
|
||||
"Vysunout"
|
||||
|
||||
#
|
||||
#MSG_TOTAL_FAILURES c=20
|
||||
"Total failures"
|
||||
"Celkem selhani"
|
||||
|
||||
@ -1170,7 +1182,7 @@
|
||||
"Unloading filament"
|
||||
"Vysouvam filament"
|
||||
|
||||
#
|
||||
#MSG_TOTAL c=6
|
||||
"Total"
|
||||
"Celkem"
|
||||
|
||||
@ -1338,7 +1350,7 @@
|
||||
"Warn"
|
||||
"Varovat"
|
||||
|
||||
#
|
||||
#MSG_HW_SETUP c=18
|
||||
"HW Setup"
|
||||
"HW nastaveni"
|
||||
|
||||
@ -1354,10 +1366,6 @@
|
||||
"Mesh"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Mesh Bed Leveling"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"MK3S firmware detekovan na tiskarne MK3"
|
||||
@ -1386,11 +1394,11 @@
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
"\x00"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-code je pripraven pro jiny typ tiskarny. Pokracovat?"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
|
||||
"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."
|
||||
|
||||
@ -1446,7 +1454,7 @@
|
||||
"Assist"
|
||||
"Asist."
|
||||
|
||||
# c=18
|
||||
#MSG_STEEL_SHEET c=18
|
||||
"Steel sheets"
|
||||
"Tiskove platy"
|
||||
|
||||
|
90
lang/lang_en_de.txt
Executable file → Normal file
90
lang/lang_en_de.txt
Executable file → Normal file
@ -2,14 +2,26 @@
|
||||
"[%.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_03_OR_OLDER c=18
|
||||
#MSG_IR_03_OR_OLDER c=18
|
||||
" 0.3 or older"
|
||||
" 0.3 oder aelter"
|
||||
|
||||
#MSG_04_OR_NEWER c=18
|
||||
# c=18
|
||||
"FS v0.3 or older"
|
||||
"FS 0.3 oder aelter"
|
||||
|
||||
#MSG_IR_04_OR_NEWER c=18
|
||||
" 0.4 or newer"
|
||||
" 0.4 oder neuer"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS 0.4 oder neuer"
|
||||
|
||||
#MSG_IR_UNKNOWN c=18
|
||||
"unknown state"
|
||||
"Status unbekannt"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" von 4"
|
||||
@ -126,7 +138,7 @@
|
||||
"Bed"
|
||||
"Bett"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=18
|
||||
#MSG_BELT_STATUS c=18
|
||||
"Belt status"
|
||||
"Gurtstatus"
|
||||
|
||||
@ -206,7 +218,7 @@
|
||||
"Crash detected. Resume print?"
|
||||
"Crash erkannt. Druck fortfuehren?"
|
||||
|
||||
#
|
||||
#MSG_CRASH c=7
|
||||
"Crash"
|
||||
"\x00"
|
||||
|
||||
@ -238,7 +250,7 @@
|
||||
"E-correct:"
|
||||
"E-Korrektur:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
#MSG_EJECT_FILAMENT c=16
|
||||
"Eject filament"
|
||||
"Filamentauswurf"
|
||||
|
||||
@ -294,7 +306,7 @@
|
||||
"Extruder info"
|
||||
"Extruder Info"
|
||||
|
||||
#MSG_MOVE_E
|
||||
#MSG_EXTRUDER c=17
|
||||
"Extruder"
|
||||
"\x00"
|
||||
|
||||
@ -318,7 +330,7 @@
|
||||
"Fan test"
|
||||
"Lueftertest"
|
||||
|
||||
#MSG_FANS_CHECK
|
||||
#MSG_FANS_CHECK c=13
|
||||
"Fans check"
|
||||
"Luefter Chk."
|
||||
|
||||
@ -326,9 +338,9 @@
|
||||
"Fil. sensor"
|
||||
"Fil. Sensor"
|
||||
|
||||
# c=14
|
||||
"Filam. runouts"
|
||||
"Filam. Maengel"
|
||||
#MSG_FIL_RUNOUTS c=14
|
||||
"Fil. runouts "
|
||||
"Fil. Maengel "
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
@ -354,10 +366,6 @@
|
||||
"FS Action"
|
||||
"FS Aktion"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS v0.4 oder neuer"
|
||||
|
||||
#MSG_FILE_INCOMPLETE c=20 r=3
|
||||
"File incomplete. Continue anyway?"
|
||||
"Datei unvollstaendig Trotzdem fortfahren?"
|
||||
@ -450,17 +458,17 @@
|
||||
"Checking sensors "
|
||||
"Pruefe Sensoren "
|
||||
|
||||
#MSG_SELFTEST_CHECK_X c=20
|
||||
"Checking X axis "
|
||||
"Pruefe X Achse "
|
||||
#MSG_CHECKING_X c=20
|
||||
"Checking X axis"
|
||||
"Pruefe X Achse"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Y c=20
|
||||
"Checking Y axis "
|
||||
"Pruefe Y Achse "
|
||||
#MSG_CHECKING_Y c=20
|
||||
"Checking Y axis"
|
||||
"Pruefe Y Achse"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Z c=20
|
||||
"Checking Z axis "
|
||||
"Pruefe Z Achse "
|
||||
"Checking Z axis"
|
||||
"Pruefe Z Achse"
|
||||
|
||||
#MSG_CHOOSE_EXTRUDER c=20 r=1
|
||||
"Choose extruder:"
|
||||
@ -490,7 +498,7 @@
|
||||
"Insert filament"
|
||||
"Filament einlegen"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
#MSG_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
"Ist das Filament geladen?"
|
||||
|
||||
@ -498,7 +506,7 @@
|
||||
"Is steel sheet on heatbed?"
|
||||
"Liegt das Stahlblech auf dem Heizbett?"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT_FAILURES c=20
|
||||
"Last print failures"
|
||||
"Letzte Druckfehler"
|
||||
|
||||
@ -506,7 +514,7 @@
|
||||
"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."
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT c=18
|
||||
"Last print"
|
||||
"Letzter Druck"
|
||||
|
||||
@ -574,7 +582,7 @@
|
||||
"Measuring reference height of calibration point"
|
||||
"Messen der Referenzhoehe des Kalibrierpunktes"
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
#MSG_MESH_BED_LEVELING c=18
|
||||
"Mesh Bed Leveling"
|
||||
"MeshBett Ausgleich"
|
||||
|
||||
@ -590,7 +598,7 @@
|
||||
"Measured skew"
|
||||
"Schraeglauf"
|
||||
|
||||
#
|
||||
#MSG_MMU_FAILS c=14
|
||||
"MMU fails"
|
||||
"MMU Fehler"
|
||||
|
||||
@ -598,7 +606,7 @@
|
||||
"MMU load failed "
|
||||
"MMU Ladefehler"
|
||||
|
||||
#
|
||||
#MSG_MMU_LOAD_FAILS c=14
|
||||
"MMU load fails"
|
||||
"MMU Ladefehler"
|
||||
|
||||
@ -826,7 +834,7 @@
|
||||
"Pause"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
#MSG_POWER_FAILURES c=14
|
||||
"Power failures"
|
||||
"Netzfehler"
|
||||
|
||||
@ -894,6 +902,10 @@
|
||||
"Please unload the filament first, then repeat this action."
|
||||
"Bitte entladen Sie erst das Filament und versuchen Sie es nochmal."
|
||||
|
||||
# c=20 r=4
|
||||
"Please check the IR sensor connection, unload filament if present."
|
||||
"Bitte IR Sensor Verbindungen ueber- pruefen und Filament entladen ist."
|
||||
|
||||
#MSG_RECOVERING_PRINT c=20
|
||||
"Recovering print "
|
||||
"Druck wiederherst "
|
||||
@ -910,11 +922,11 @@
|
||||
"Reset XYZ calibr."
|
||||
"Reset XYZ Kalibr."
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
#MSG_RESET c=14
|
||||
"Reset"
|
||||
"Ruecksetzen"
|
||||
|
||||
#MSG_RESUME_PRINT
|
||||
#MSG_RESUME_PRINT c=18
|
||||
"Resume print"
|
||||
"Druck fortsetzen"
|
||||
|
||||
@ -1150,7 +1162,7 @@
|
||||
"Unload"
|
||||
"Entladen"
|
||||
|
||||
#
|
||||
#MSG_TOTAL_FAILURES c=20
|
||||
"Total failures"
|
||||
"Gesamte Fehler"
|
||||
|
||||
@ -1170,7 +1182,7 @@
|
||||
"Unloading filament"
|
||||
"Filament auswerfen"
|
||||
|
||||
#
|
||||
#MSG_TOTAL c=6
|
||||
"Total"
|
||||
"Gesamt"
|
||||
|
||||
@ -1338,7 +1350,7 @@
|
||||
"Warn"
|
||||
"Warnen"
|
||||
|
||||
#
|
||||
#MSG_HW_SETUP c=18
|
||||
"HW Setup"
|
||||
"HW Einstellungen"
|
||||
|
||||
@ -1354,10 +1366,6 @@
|
||||
"Mesh"
|
||||
"Gitter"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"MeshBett Ausgleich"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"MK3S-Firmware auf MK3-Drucker erkannt"
|
||||
@ -1386,11 +1394,11 @@
|
||||
"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."
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-Code ist fuer einen anderen Drucker geslict. Fortfahren?"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
|
||||
"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."
|
||||
|
||||
@ -1446,7 +1454,7 @@
|
||||
"Assist"
|
||||
"\x00"
|
||||
|
||||
# c=18
|
||||
#MSG_STEEL_SHEET c=18
|
||||
"Steel sheets"
|
||||
"Stahlbleche"
|
||||
|
||||
|
88
lang/lang_en_es.txt
Executable file → Normal file
88
lang/lang_en_es.txt
Executable file → Normal file
@ -2,14 +2,26 @@
|
||||
"[%.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_03_OR_OLDER c=18
|
||||
#MSG_IR_03_OR_OLDER c=18
|
||||
" 0.3 or older"
|
||||
" 0.3 o mayor"
|
||||
|
||||
#MSG_04_OR_NEWER c=18
|
||||
# c=18
|
||||
"FS v0.3 or older"
|
||||
"FS 0.3 o mayor"
|
||||
|
||||
#MSG_IR_04_OR_NEWER c=18
|
||||
" 0.4 or newer"
|
||||
" 0.4 o mas nueva"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS 0.4 o mas nueva"
|
||||
|
||||
#MSG_IR_UNKNOWN c=18
|
||||
"unknown state"
|
||||
"estado desconocido"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" de 4"
|
||||
@ -126,7 +138,7 @@
|
||||
"Bed"
|
||||
"Base"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=18
|
||||
#MSG_BELT_STATUS c=18
|
||||
"Belt status"
|
||||
"Estado de correa"
|
||||
|
||||
@ -206,7 +218,7 @@
|
||||
"Crash detected. Resume print?"
|
||||
"Choque detectado. Continuar impresion?"
|
||||
|
||||
#
|
||||
#MSG_CRASH c=7
|
||||
"Crash"
|
||||
"Choque"
|
||||
|
||||
@ -238,7 +250,7 @@
|
||||
"E-correct:"
|
||||
"Corregir-E:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
#MSG_EJECT_FILAMENT c=16
|
||||
"Eject filament"
|
||||
"Expulsar fil."
|
||||
|
||||
@ -294,7 +306,7 @@
|
||||
"Extruder info"
|
||||
"Info. del extrusor"
|
||||
|
||||
#MSG_MOVE_E
|
||||
#MSG_EXTRUDER c=17
|
||||
"Extruder"
|
||||
"Extruir"
|
||||
|
||||
@ -318,7 +330,7 @@
|
||||
"Fan test"
|
||||
"Test ventiladores"
|
||||
|
||||
#MSG_FANS_CHECK
|
||||
#MSG_FANS_CHECK c=13
|
||||
"Fans check"
|
||||
"Comprob.vent"
|
||||
|
||||
@ -326,9 +338,9 @@
|
||||
"Fil. sensor"
|
||||
"Sensor Fil."
|
||||
|
||||
# c=14
|
||||
"Filam. runouts"
|
||||
"Filam. acabado"
|
||||
#MSG_FIL_RUNOUTS c=14
|
||||
"Fil. runouts "
|
||||
"Fil. acabado "
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
@ -354,10 +366,6 @@
|
||||
"FS Action"
|
||||
"FS accion"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS v0.4 o +nueva"
|
||||
|
||||
#MSG_FILE_INCOMPLETE c=20 r=3
|
||||
"File incomplete. Continue anyway?"
|
||||
"Archivo incompleto. ?Continuar de todos modos?"
|
||||
@ -450,16 +458,16 @@
|
||||
"Checking sensors "
|
||||
"Comprobando sensores"
|
||||
|
||||
#MSG_SELFTEST_CHECK_X c=20
|
||||
"Checking X axis "
|
||||
#MSG_CHECKING_X c=20
|
||||
"Checking X axis"
|
||||
"Control sensor X"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Y c=20
|
||||
"Checking Y axis "
|
||||
#MSG_CHECKING_Y c=20
|
||||
"Checking Y axis"
|
||||
"Control sensor Y"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Z c=20
|
||||
"Checking Z axis "
|
||||
"Checking Z axis"
|
||||
"Control sensor Z"
|
||||
|
||||
#MSG_CHOOSE_EXTRUDER c=20 r=1
|
||||
@ -490,7 +498,7 @@
|
||||
"Insert filament"
|
||||
"Introducir filamento"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
#MSG_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
"Esta el filamento cargado?"
|
||||
|
||||
@ -498,15 +506,15 @@
|
||||
"Is steel sheet on heatbed?"
|
||||
"?Esta colocada la lamina sobre la base"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT_FAILURES c=20
|
||||
"Last print failures"
|
||||
"Ultimas impresiones fallidas"
|
||||
"Ultimos imp. fallos"
|
||||
|
||||
#
|
||||
"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."
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT c=18
|
||||
"Last print"
|
||||
"Ultima impresion"
|
||||
|
||||
@ -574,9 +582,9 @@
|
||||
"Measuring reference height of calibration point"
|
||||
"Midiendo altura del punto de calibracion"
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
#MSG_MESH_BED_LEVELING c=18
|
||||
"Mesh Bed Leveling"
|
||||
"Nivelacion Mesh Level"
|
||||
"Nivela. Mesh Level"
|
||||
|
||||
#MSG_MMU_OK_RESUMING_POSITION c=20 r=4
|
||||
"MMU OK. Resuming position..."
|
||||
@ -590,7 +598,7 @@
|
||||
"Measured skew"
|
||||
"Desviacion med:"
|
||||
|
||||
#
|
||||
#MSG_MMU_FAILS c=14
|
||||
"MMU fails"
|
||||
"Fallos MMU"
|
||||
|
||||
@ -598,7 +606,7 @@
|
||||
"MMU load failed "
|
||||
"Carga MMU fallida"
|
||||
|
||||
#
|
||||
#MSG_MMU_LOAD_FAILS c=14
|
||||
"MMU load fails"
|
||||
"Carga MMU falla"
|
||||
|
||||
@ -826,7 +834,7 @@
|
||||
"Pause"
|
||||
"Pausa"
|
||||
|
||||
#
|
||||
#MSG_POWER_FAILURES c=14
|
||||
"Power failures"
|
||||
"Cortes de energia"
|
||||
|
||||
@ -894,6 +902,10 @@
|
||||
"Please unload the filament first, then repeat this action."
|
||||
"Primero descargue el filamento, luego repita esta accion."
|
||||
|
||||
# c=20 r=4
|
||||
"Please check the IR sensor connection, unload filament if present."
|
||||
"Por favor comprueba la conexion del IR sensor y filamento esta descargado."
|
||||
|
||||
#MSG_RECOVERING_PRINT c=20
|
||||
"Recovering print "
|
||||
"Recuper. impresion "
|
||||
@ -910,11 +922,11 @@
|
||||
"Reset XYZ calibr."
|
||||
"\x00"
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
#MSG_RESET c=14
|
||||
"Reset"
|
||||
"\x00"
|
||||
|
||||
#MSG_RESUME_PRINT
|
||||
#MSG_RESUME_PRINT c=18
|
||||
"Resume print"
|
||||
"Reanudar impres."
|
||||
|
||||
@ -1150,7 +1162,7 @@
|
||||
"Unload"
|
||||
"Descargar"
|
||||
|
||||
#
|
||||
#MSG_TOTAL_FAILURES c=20
|
||||
"Total failures"
|
||||
"Fallos totales"
|
||||
|
||||
@ -1170,7 +1182,7 @@
|
||||
"Unloading filament"
|
||||
"Soltando filamento"
|
||||
|
||||
#
|
||||
#MSG_TOTAL c=6
|
||||
"Total"
|
||||
"\x00"
|
||||
|
||||
@ -1338,7 +1350,7 @@
|
||||
"Warn"
|
||||
"Aviso"
|
||||
|
||||
#
|
||||
#MSG_HW_SETUP c=18
|
||||
"HW Setup"
|
||||
"Configuracion HW"
|
||||
|
||||
@ -1354,10 +1366,6 @@
|
||||
"Mesh"
|
||||
"Malla"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Nivelacion Malla Base"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"Firmware MK3S detectado en impresora MK3"
|
||||
@ -1386,11 +1394,11 @@
|
||||
"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."
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"Codigo G laminado para un tipo de impresora diferente. ?Continuar?"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
|
||||
"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."
|
||||
|
||||
@ -1446,7 +1454,7 @@
|
||||
"Assist"
|
||||
"Asistido"
|
||||
|
||||
# c=18
|
||||
#MSG_STEEL_SHEET c=18
|
||||
"Steel sheets"
|
||||
"Lamina de acero"
|
||||
|
||||
|
84
lang/lang_en_fr.txt
Executable file → Normal file
84
lang/lang_en_fr.txt
Executable file → Normal file
@ -2,14 +2,26 @@
|
||||
"[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
|
||||
"[%.7s]Ajust. du Z\x0aValeur enreg, contin\x0aou depart a zero?\x0a%cContinuer%cReset"
|
||||
|
||||
#MSG_03_OR_OLDER c=18
|
||||
#MSG_IR_03_OR_OLDER c=18
|
||||
" 0.3 or older"
|
||||
" 0.3 ou +ancien"
|
||||
|
||||
#MSG_04_OR_NEWER c=18
|
||||
# c=18
|
||||
"FS v0.3 or older"
|
||||
"FS v0.3 ou +ancien"
|
||||
|
||||
#MSG_IR_04_OR_NEWER c=18
|
||||
" 0.4 or newer"
|
||||
" 0.4 ou +recent"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS v0.4 ou +recent"
|
||||
|
||||
#MSG_IR_UNKNOWN c=18
|
||||
"unknown state"
|
||||
"Etat inconnu"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" de 4"
|
||||
@ -126,7 +138,7 @@
|
||||
"Bed"
|
||||
"Lit"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=18
|
||||
#MSG_BELT_STATUS c=18
|
||||
"Belt status"
|
||||
"Statut courroie"
|
||||
|
||||
@ -206,7 +218,7 @@
|
||||
"Crash detected. Resume print?"
|
||||
"Crash detecte. Poursuivre l'impression?"
|
||||
|
||||
#
|
||||
#MSG_CRASH c=7
|
||||
"Crash"
|
||||
"\x00"
|
||||
|
||||
@ -238,7 +250,7 @@
|
||||
"E-correct:"
|
||||
"Correct-E:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
#MSG_EJECT_FILAMENT c=16
|
||||
"Eject filament"
|
||||
"Remonter le fil."
|
||||
|
||||
@ -294,7 +306,7 @@
|
||||
"Extruder info"
|
||||
"Infos extrudeur"
|
||||
|
||||
#MSG_MOVE_E
|
||||
#MSG_EXTRUDER c=17
|
||||
"Extruder"
|
||||
"Extrudeur"
|
||||
|
||||
@ -318,7 +330,7 @@
|
||||
"Fan test"
|
||||
"Test du ventilateur"
|
||||
|
||||
#MSG_FANS_CHECK
|
||||
#MSG_FANS_CHECK c=13
|
||||
"Fans check"
|
||||
"Verif vent."
|
||||
|
||||
@ -326,9 +338,9 @@
|
||||
"Fil. sensor"
|
||||
"Capteur Fil."
|
||||
|
||||
# c=14
|
||||
"Filam. runouts"
|
||||
"Fins filament"
|
||||
#MSG_FIL_RUNOUTS c=14
|
||||
"Fil. runouts "
|
||||
"Fins filament "
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
@ -354,10 +366,6 @@
|
||||
"FS Action"
|
||||
"\x00"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS v0.4 ou +recent"
|
||||
|
||||
#MSG_FILE_INCOMPLETE c=20 r=3
|
||||
"File incomplete. Continue anyway?"
|
||||
"Fichier incomplet. Continuer qd meme?"
|
||||
@ -450,16 +458,16 @@
|
||||
"Checking sensors "
|
||||
"Verif. des capteurs"
|
||||
|
||||
#MSG_SELFTEST_CHECK_X c=20
|
||||
"Checking X axis "
|
||||
#MSG_CHECKING_X c=20
|
||||
"Checking X axis"
|
||||
"Verification axe X"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Y c=20
|
||||
"Checking Y axis "
|
||||
#MSG_CHECKING_Y c=20
|
||||
"Checking Y axis"
|
||||
"Verification axe Y"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Z c=20
|
||||
"Checking Z axis "
|
||||
"Checking Z axis"
|
||||
"Verification axe Z"
|
||||
|
||||
#MSG_CHOOSE_EXTRUDER c=20 r=1
|
||||
@ -490,7 +498,7 @@
|
||||
"Insert filament"
|
||||
"Inserez le filament"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
#MSG_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
"Fil. est-il charge?"
|
||||
|
||||
@ -498,7 +506,7 @@
|
||||
"Is steel sheet on heatbed?"
|
||||
"Est la plaque sur le plat. chauffant?"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT_FAILURES c=20
|
||||
"Last print failures"
|
||||
"Echecs derniere imp."
|
||||
|
||||
@ -506,7 +514,7 @@
|
||||
"If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
|
||||
"Si vous avez d'autres feuilles d'acier, calibrez leurs pre-reglages dans Reglages - Config HW - Plaque en acier."
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT c=18
|
||||
"Last print"
|
||||
"Derniere impres."
|
||||
|
||||
@ -574,7 +582,7 @@
|
||||
"Measuring reference height of calibration point"
|
||||
"Je mesure la hauteur de reference du point de calibrage"
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
#MSG_MESH_BED_LEVELING c=18
|
||||
"Mesh Bed Leveling"
|
||||
"\x00"
|
||||
|
||||
@ -590,7 +598,7 @@
|
||||
"Measured skew"
|
||||
"Deviat.mesuree"
|
||||
|
||||
#
|
||||
#MSG_MMU_FAILS c=14
|
||||
"MMU fails"
|
||||
"Echecs MMU"
|
||||
|
||||
@ -598,7 +606,7 @@
|
||||
"MMU load failed "
|
||||
"Echec chargement MMU"
|
||||
|
||||
#
|
||||
#MSG_MMU_LOAD_FAILS c=14
|
||||
"MMU load fails"
|
||||
"Echecs charg. MMU"
|
||||
|
||||
@ -826,7 +834,7 @@
|
||||
"Pause"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
#MSG_POWER_FAILURES c=14
|
||||
"Power failures"
|
||||
"Coup.de courant"
|
||||
|
||||
@ -894,6 +902,10 @@
|
||||
"Please unload the filament first, then repeat this action."
|
||||
"SVP, dechargez le filament et reessayez."
|
||||
|
||||
# c=20 r=4
|
||||
"Please check the IR sensor connection, unload filament if present."
|
||||
"SVP, verifiez la connexion du capteur IR et decharge le filament."
|
||||
|
||||
#MSG_RECOVERING_PRINT c=20
|
||||
"Recovering print "
|
||||
"Recup. impression "
|
||||
@ -910,11 +922,11 @@
|
||||
"Reset XYZ calibr."
|
||||
"Reinit. calib. XYZ"
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
#MSG_RESET c=14
|
||||
"Reset"
|
||||
"Reinitialiser"
|
||||
|
||||
#MSG_RESUME_PRINT
|
||||
#MSG_RESUME_PRINT c=18
|
||||
"Resume print"
|
||||
"Reprendre impression"
|
||||
|
||||
@ -1150,7 +1162,7 @@
|
||||
"Unload"
|
||||
"Decharger"
|
||||
|
||||
#
|
||||
#MSG_TOTAL_FAILURES c=20
|
||||
"Total failures"
|
||||
"Total des echecs"
|
||||
|
||||
@ -1170,7 +1182,7 @@
|
||||
"Unloading filament"
|
||||
"Dechargement fil."
|
||||
|
||||
#
|
||||
#MSG_TOTAL c=6
|
||||
"Total"
|
||||
"Totale"
|
||||
|
||||
@ -1338,7 +1350,7 @@
|
||||
"Warn"
|
||||
"Avert"
|
||||
|
||||
#
|
||||
#MSG_HW_SETUP c=18
|
||||
"HW Setup"
|
||||
"Config HW"
|
||||
|
||||
@ -1354,10 +1366,6 @@
|
||||
"Mesh"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"\x00"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"Firmware MK3S detecte sur imprimante MK3"
|
||||
@ -1386,11 +1394,11 @@
|
||||
"G-code sliced for a different level. Please re-slice the model again. Print cancelled."
|
||||
"Le G-code a ete prepare pour un niveau different. Veuillez decouper le modele a nouveau. L'impression a ete annulee."
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"Le G-code a ete prepare pour une autre version de l'imprimante. Continuer?"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
|
||||
"G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
|
||||
"Le G-code a ete prepare pour une autre version de l'imprimante. Veuillez decouper le modele a nouveau. L'impression a ete annulee."
|
||||
|
||||
@ -1446,7 +1454,7 @@
|
||||
"Assist"
|
||||
"\x00"
|
||||
|
||||
# c=18
|
||||
#MSG_STEEL_SHEET c=18
|
||||
"Steel sheets"
|
||||
"Plaques en acier"
|
||||
|
||||
|
86
lang/lang_en_it.txt
Executable file → Normal file
86
lang/lang_en_it.txt
Executable file → Normal file
@ -6,10 +6,22 @@
|
||||
" 0.3 or older"
|
||||
" 0.3 o inferiore"
|
||||
|
||||
#MSG_04_OR_NEWER c=18
|
||||
# c=18
|
||||
"FS v0.3 or older"
|
||||
"FS 0.3 o inferiore"
|
||||
|
||||
#MSG_IR_04_OR_NEWER c=18
|
||||
" 0.4 or newer"
|
||||
" 0.4 o superiore"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS 0.4 o superiore"
|
||||
|
||||
#MSG_IR_UNKNOWN c=18
|
||||
"unknown state"
|
||||
"stato sconosciuto"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" su 4"
|
||||
@ -126,7 +138,7 @@
|
||||
"Bed"
|
||||
"Piano"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=18
|
||||
#MSG_BELT_STATUS c=18
|
||||
"Belt status"
|
||||
"Stato cinghie"
|
||||
|
||||
@ -206,7 +218,7 @@
|
||||
"Crash detected. Resume print?"
|
||||
"Scontro rilevato. Riprendere la stampa?"
|
||||
|
||||
#
|
||||
#MSG_CRASH c=7
|
||||
"Crash"
|
||||
"Impatto"
|
||||
|
||||
@ -238,9 +250,9 @@
|
||||
"E-correct:"
|
||||
"Correzione-E:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
#MSG_EJECT_FILAMENT c=16
|
||||
"Eject filament"
|
||||
"Espelli filamento"
|
||||
"Espelli fil."
|
||||
|
||||
#MSG_EJECTING_FILAMENT c=20 r=1
|
||||
"Ejecting filament"
|
||||
@ -294,7 +306,7 @@
|
||||
"Extruder info"
|
||||
"Info estrusore"
|
||||
|
||||
#MSG_MOVE_E
|
||||
#MSG_EXTRUDER c=17
|
||||
"Extruder"
|
||||
"Estrusore"
|
||||
|
||||
@ -318,7 +330,7 @@
|
||||
"Fan test"
|
||||
"Test ventola"
|
||||
|
||||
#MSG_FANS_CHECK
|
||||
#MSG_FANS_CHECK c=13
|
||||
"Fans check"
|
||||
"Control.vent"
|
||||
|
||||
@ -326,9 +338,9 @@
|
||||
"Fil. sensor"
|
||||
"Sensore fil."
|
||||
|
||||
# c=14
|
||||
"Filam. runouts"
|
||||
"Fil. esauriti"
|
||||
#MSG_FIL_RUNOUTS c=14
|
||||
"Fil. runouts "
|
||||
"Fil. esauriti "
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
"Filament extruding & with correct color?"
|
||||
@ -354,10 +366,6 @@
|
||||
"FS Action"
|
||||
"Azione FS"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS 0.4 o superiore"
|
||||
|
||||
#MSG_FILE_INCOMPLETE c=20 r=3
|
||||
"File incomplete. Continue anyway?"
|
||||
"File incompleto. Continuare comunque?"
|
||||
@ -450,16 +458,16 @@
|
||||
"Checking sensors "
|
||||
"Controllo sensori"
|
||||
|
||||
#MSG_SELFTEST_CHECK_X c=20
|
||||
"Checking X axis "
|
||||
#MSG_CHECKING_X c=20
|
||||
"Checking X axis"
|
||||
"Verifica asse X"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Y c=20
|
||||
"Checking Y axis "
|
||||
#MSG_CHECKING_Y c=20
|
||||
"Checking Y axis"
|
||||
"Verifica asse Y"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Z c=20
|
||||
"Checking Z axis "
|
||||
"Checking Z axis"
|
||||
"Verifica asse Z"
|
||||
|
||||
#MSG_CHOOSE_EXTRUDER c=20 r=1
|
||||
@ -490,7 +498,7 @@
|
||||
"Insert filament"
|
||||
"Inserire filamento"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
#MSG_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
"Il filamento e' stato caricato?"
|
||||
|
||||
@ -498,15 +506,15 @@
|
||||
"Is steel sheet on heatbed?"
|
||||
"Piastra d'acciaio su piano riscaldato?"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT_FAILURES c=20
|
||||
"Last print failures"
|
||||
"Fallimenti ultima stampa"
|
||||
"Errori 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."
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT c=18
|
||||
"Last print"
|
||||
"Ultima stampa"
|
||||
|
||||
@ -574,7 +582,7 @@
|
||||
"Measuring reference height of calibration point"
|
||||
"Misura altezza di rif. del punto di calib."
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
#MSG_MESH_BED_LEVELING c=18
|
||||
"Mesh Bed Leveling"
|
||||
"Liv. grilia piano"
|
||||
|
||||
@ -590,7 +598,7 @@
|
||||
"Measured skew"
|
||||
"Deviazione mis"
|
||||
|
||||
#
|
||||
#MSG_MMU_FAILS c=14
|
||||
"MMU fails"
|
||||
"Fallimenti MMU"
|
||||
|
||||
@ -598,7 +606,7 @@
|
||||
"MMU load failed "
|
||||
"Caricamento MMU fallito"
|
||||
|
||||
#
|
||||
#MSG_MMU_LOAD_FAILS c=14
|
||||
"MMU load fails"
|
||||
"Caricamenti MMU falliti"
|
||||
|
||||
@ -826,7 +834,7 @@
|
||||
"Pause"
|
||||
"Pausa"
|
||||
|
||||
#
|
||||
#MSG_POWER_FAILURES c=14
|
||||
"Power failures"
|
||||
"Mancanza corrente"
|
||||
|
||||
@ -894,6 +902,10 @@
|
||||
"Please unload the filament first, then repeat this action."
|
||||
"Scaricare prima il filamento, poi ripetere l'operazione."
|
||||
|
||||
# c=20 r=4
|
||||
"Please check the IR sensor connection, unload filament if present."
|
||||
"Controllare il collegamento al sensore e rimuovere il filamento."
|
||||
|
||||
#MSG_RECOVERING_PRINT c=20
|
||||
"Recovering print "
|
||||
"Recupero stampa "
|
||||
@ -910,11 +922,11 @@
|
||||
"Reset XYZ calibr."
|
||||
"Reset calibrazione XYZ."
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
#MSG_RESET c=14
|
||||
"Reset"
|
||||
"\x00"
|
||||
|
||||
#MSG_RESUME_PRINT
|
||||
#MSG_RESUME_PRINT c=18
|
||||
"Resume print"
|
||||
"Riprendi stampa"
|
||||
|
||||
@ -1150,7 +1162,7 @@
|
||||
"Unload"
|
||||
"Scarica"
|
||||
|
||||
#
|
||||
#MSG_TOTAL_FAILURES c=20
|
||||
"Total failures"
|
||||
"Totale fallimenti"
|
||||
|
||||
@ -1170,7 +1182,7 @@
|
||||
"Unloading filament"
|
||||
"Scaricando filamento"
|
||||
|
||||
#
|
||||
#MSG_TOTAL c=6
|
||||
"Total"
|
||||
"Totale"
|
||||
|
||||
@ -1338,7 +1350,7 @@
|
||||
"Warn"
|
||||
"Avviso"
|
||||
|
||||
#
|
||||
#MSG_HW_SETUP c=18
|
||||
"HW Setup"
|
||||
"Impostazioni HW"
|
||||
|
||||
@ -1354,10 +1366,6 @@
|
||||
"Mesh"
|
||||
"Griglia"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Liv. griglia piano"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"Firmware MK3S rilevato su stampante MK3"
|
||||
@ -1386,11 +1394,11 @@
|
||||
"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."
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-code processato per una stampante diversa. Continuare?"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
|
||||
"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."
|
||||
|
||||
@ -1446,7 +1454,7 @@
|
||||
"Assist"
|
||||
"Assist."
|
||||
|
||||
# c=18
|
||||
#MSG_STEEL_SHEET c=18
|
||||
"Steel sheets"
|
||||
"Piani d'acciaio"
|
||||
|
||||
|
86
lang/lang_en_pl.txt
Executable file → Normal file
86
lang/lang_en_pl.txt
Executable file → Normal file
@ -2,14 +2,26 @@
|
||||
"[%.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_03_OR_OLDER c=18
|
||||
#MSG_IR_03_OR_OLDER c=18
|
||||
" 0.3 or older"
|
||||
" 0.3 lub starszy"
|
||||
|
||||
#MSG_04_OR_NEWER c=18
|
||||
# c=18
|
||||
"FS v0.3 or older"
|
||||
"FS 0.3 lub starszy"
|
||||
|
||||
#MSG_IR_04_OR_NEWER c=18
|
||||
" 0.4 or newer"
|
||||
" 0.4 lub nowszy"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS 0.4 lub nowszy"
|
||||
|
||||
#MSG_IR_UNKNOWN c=18
|
||||
"unknown state"
|
||||
"Stan nieznany"
|
||||
|
||||
#MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
|
||||
" of 4"
|
||||
" z 4"
|
||||
@ -126,7 +138,7 @@
|
||||
"Bed"
|
||||
"Stol"
|
||||
|
||||
#MSG_MENU_BELT_STATUS c=18
|
||||
#MSG_BELT_STATUS c=18
|
||||
"Belt status"
|
||||
"Stan paskow"
|
||||
|
||||
@ -206,9 +218,9 @@
|
||||
"Crash detected. Resume print?"
|
||||
"Wykryto zderzenie. Wznowic druk?"
|
||||
|
||||
#
|
||||
#MSG_CRASH c=7
|
||||
"Crash"
|
||||
"Zderzenie"
|
||||
"Zderzen"
|
||||
|
||||
#MSG_CURRENT c=19 r=1
|
||||
"Current"
|
||||
@ -238,7 +250,7 @@
|
||||
"E-correct:"
|
||||
"Korekcja-E:"
|
||||
|
||||
#MSG_EJECT_FILAMENT c=17 r=1
|
||||
#MSG_EJECT_FILAMENT c=16
|
||||
"Eject filament"
|
||||
"Wysun filament"
|
||||
|
||||
@ -294,7 +306,7 @@
|
||||
"Extruder info"
|
||||
"Ekstruder - info"
|
||||
|
||||
#MSG_MOVE_E
|
||||
#MSG_EXTRUDER c=17
|
||||
"Extruder"
|
||||
"Ekstruder"
|
||||
|
||||
@ -318,7 +330,7 @@
|
||||
"Fan test"
|
||||
"Test wentylatora"
|
||||
|
||||
#MSG_FANS_CHECK
|
||||
#MSG_FANS_CHECK c=13
|
||||
"Fans check"
|
||||
"Sprawd.went."
|
||||
|
||||
@ -326,8 +338,8 @@
|
||||
"Fil. sensor"
|
||||
"Czuj. filam."
|
||||
|
||||
# c=14
|
||||
"Filam. runouts"
|
||||
#MSG_FIL_RUNOUTS c=14
|
||||
"Fil. runouts "
|
||||
"Konc.filamentu"
|
||||
|
||||
#MSG_FILAMENT_CLEAN c=20 r=2
|
||||
@ -354,10 +366,6 @@
|
||||
"FS Action"
|
||||
"Akcja FS"
|
||||
|
||||
# c=18
|
||||
"FS v0.4 or newer"
|
||||
"FS v0.4 lub nowszy"
|
||||
|
||||
#MSG_FILE_INCOMPLETE c=20 r=3
|
||||
"File incomplete. Continue anyway?"
|
||||
"Plik niekompletny. Kontynowac?"
|
||||
@ -450,16 +458,16 @@
|
||||
"Checking sensors "
|
||||
"Kontrola czujnikow"
|
||||
|
||||
#MSG_SELFTEST_CHECK_X c=20
|
||||
"Checking X axis "
|
||||
#MSG_CHECKING_X c=20
|
||||
"Checking X axis"
|
||||
"Kontrola osi X"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Y c=20
|
||||
"Checking Y axis "
|
||||
#MSG_CHECKING_Y c=20
|
||||
"Checking Y axis"
|
||||
"Kontrola osi Y"
|
||||
|
||||
#MSG_SELFTEST_CHECK_Z c=20
|
||||
"Checking Z axis "
|
||||
"Checking Z axis"
|
||||
"Kontrola osi Z"
|
||||
|
||||
#MSG_CHOOSE_EXTRUDER c=20 r=1
|
||||
@ -490,7 +498,7 @@
|
||||
"Insert filament"
|
||||
"Wprowadz filament"
|
||||
|
||||
#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
|
||||
#MSG_FILAMENT_LOADED c=20 r=2
|
||||
"Is filament loaded?"
|
||||
"Filament jest zaladowany?"
|
||||
|
||||
@ -498,7 +506,7 @@
|
||||
"Is steel sheet on heatbed?"
|
||||
"Czy plyta stal. jest na podgrzew. stole?"
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT_FAILURES c=20
|
||||
"Last print failures"
|
||||
"Ostatnie bledy druku"
|
||||
|
||||
@ -506,7 +514,7 @@
|
||||
"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."
|
||||
|
||||
#
|
||||
#MSG_LAST_PRINT c=18
|
||||
"Last print"
|
||||
"Ost. wydruk"
|
||||
|
||||
@ -574,9 +582,9 @@
|
||||
"Measuring reference height of calibration point"
|
||||
"Okreslam wysokosc odniesienia punktu kalibracyjnego"
|
||||
|
||||
#MSG_MESH_BED_LEVELING
|
||||
#MSG_MESH_BED_LEVELING c=18
|
||||
"Mesh Bed Leveling"
|
||||
"Poziomowanie stolu wg siatki"
|
||||
"Poziomowanie stolu"
|
||||
|
||||
#MSG_MMU_OK_RESUMING_POSITION c=20 r=4
|
||||
"MMU OK. Resuming position..."
|
||||
@ -590,7 +598,7 @@
|
||||
"Measured skew"
|
||||
"Zmierzony skos"
|
||||
|
||||
#
|
||||
#MSG_MMU_FAILS c=14
|
||||
"MMU fails"
|
||||
"Bledy MMU"
|
||||
|
||||
@ -598,7 +606,7 @@
|
||||
"MMU load failed "
|
||||
"Blad ladowania MMU"
|
||||
|
||||
#
|
||||
#MSG_MMU_LOAD_FAILS c=14
|
||||
"MMU load fails"
|
||||
"Bledy ladow. MMU"
|
||||
|
||||
@ -826,7 +834,7 @@
|
||||
"Pause"
|
||||
"Pauza"
|
||||
|
||||
#
|
||||
#MSG_POWER_FAILURES c=14
|
||||
"Power failures"
|
||||
"Zaniki zasilania"
|
||||
|
||||
@ -894,6 +902,10 @@
|
||||
"Please unload the filament first, then repeat this action."
|
||||
"Najpierw rozladuj filament, nastepnie powtorz czynnosc."
|
||||
|
||||
# c=20 r=4
|
||||
"Please check the IR sensor connection, unload filament if present."
|
||||
"Sprawdz polaczenie czujnika IR, rozladuj filament, jesli zaladowany."
|
||||
|
||||
#MSG_RECOVERING_PRINT c=20
|
||||
"Recovering print "
|
||||
"Wznawianie wydruku "
|
||||
@ -910,11 +922,11 @@
|
||||
"Reset XYZ calibr."
|
||||
"Reset kalibr. XYZ"
|
||||
|
||||
#MSG_BED_CORRECTION_RESET
|
||||
#MSG_RESET c=14
|
||||
"Reset"
|
||||
"\x00"
|
||||
|
||||
#MSG_RESUME_PRINT
|
||||
#MSG_RESUME_PRINT c=18
|
||||
"Resume print"
|
||||
"Wznowic wydruk"
|
||||
|
||||
@ -1150,7 +1162,7 @@
|
||||
"Unload"
|
||||
"Rozladuj"
|
||||
|
||||
#
|
||||
#MSG_TOTAL_FAILURES c=20
|
||||
"Total failures"
|
||||
"Suma bledow"
|
||||
|
||||
@ -1170,7 +1182,7 @@
|
||||
"Unloading filament"
|
||||
"Rozladowuje filament"
|
||||
|
||||
#
|
||||
#MSG_TOTAL c=6
|
||||
"Total"
|
||||
"Suma"
|
||||
|
||||
@ -1338,7 +1350,7 @@
|
||||
"Warn"
|
||||
"Ostrzez"
|
||||
|
||||
#
|
||||
#MSG_HW_SETUP c=18
|
||||
"HW Setup"
|
||||
"Ustawienia HW"
|
||||
|
||||
@ -1354,10 +1366,6 @@
|
||||
"Mesh"
|
||||
"Siatka"
|
||||
|
||||
#
|
||||
"Mesh bed leveling"
|
||||
"Poziomowanie stolu"
|
||||
|
||||
#
|
||||
"MK3S firmware detected on MK3 printer"
|
||||
"Wykryto firmware MK3S w drukarce MK3"
|
||||
@ -1386,11 +1394,11 @@
|
||||
"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."
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
|
||||
"G-code sliced for a different printer type. Continue?"
|
||||
"G-code pociety dla innej drukarki. Kontynuowac?"
|
||||
|
||||
#
|
||||
#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
|
||||
"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."
|
||||
|
||||
@ -1446,7 +1454,7 @@
|
||||
"Assist"
|
||||
"Asyst."
|
||||
|
||||
# c=18
|
||||
#MSG_STEEL_SHEET c=18
|
||||
"Steel sheets"
|
||||
"Plyty stalowe"
|
||||
|
||||
|
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
3694
lang/po/new/cs.po
3694
lang/po/new/cs.po
File diff suppressed because it is too large
Load Diff
3694
lang/po/new/de.po
3694
lang/po/new/de.po
File diff suppressed because it is too large
Load Diff
3694
lang/po/new/es.po
3694
lang/po/new/es.po
File diff suppressed because it is too large
Load Diff
3694
lang/po/new/fr.po
3694
lang/po/new/fr.po
File diff suppressed because it is too large
Load Diff
3694
lang/po/new/it.po
3694
lang/po/new/it.po
File diff suppressed because it is too large
Load Diff
3694
lang/po/new/pl.po
3694
lang/po/new/pl.po
File diff suppressed because it is too large
Load Diff
Loading…
Reference in New Issue
Block a user