3.0.12-RC2 sync

This commit is contained in:
PavelSindler 2017-06-29 18:35:43 +02:00
parent 0578ea527e
commit 43d696659f
41 changed files with 12029 additions and 9168 deletions

View file

@ -5,11 +5,10 @@
#include "Configuration_prusa.h"
// Firmware version
#define FW_version "3.0.10-8"
#define FW_version "3.0.12-RC2"
#define FW_PRUSA3D_MAGIC "PRUSA3DFW"
#define FW_PRUSA3D_MAGIC_LEN 10
// The total size of the EEPROM is
// 4096 for the Atmega2560
#define EEPROM_TOP 4096
@ -44,6 +43,10 @@
#define EEPROM_BED_CORRECTION_REAR (EEPROM_BED_CORRECTION_FRONT-1)
#define EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY (EEPROM_BED_CORRECTION_REAR-1)
#define EEPROM_PRINT_FLAG (EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY-1)
#define EEPROM_PROBE_TEMP_SHIFT (EEPROM_PRINT_FLAG - 2*5) //5 x int for storing pinda probe temp shift relative to 50 C; unit: motor steps
#define EEPROM_TEMP_CAL_ACTIVE (EEPROM_PROBE_TEMP_SHIFT - 1)
#define EEPROM_BOWDEN_LENGTH (EEPROM_TEMP_CAL_ACTIVE - 2*4) //4 x int for bowden lengths for multimaterial
#define EEPROM_CALIBRATION_STATUS_PINDA (EEPROM_BOWDEN_LENGTH - 1) //0 - not calibrated; 1 - calibrated
// Currently running firmware, each digit stored as uint16_t.
// The flavor differentiates a dev, alpha, beta, release candidate or a release version.
@ -246,7 +249,6 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
//#define DISABLE_MAX_ENDSTOPS
//#define DISABLE_MIN_ENDSTOPS
// Disable max endstops for compatibility with endstop checking routine
#if defined(COREXY) && !defined(DISABLE_MAX_ENDSTOPS)
#define DISABLE_MAX_ENDSTOPS
@ -265,10 +267,10 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define DISABLE_E false // For all extruders
#define DISABLE_INACTIVE_EXTRUDER true //disable only inactive extruders and keep active extruder enabled
#define INVERT_X_DIR true // for Mendel set to false, for Orca set to true
#define INVERT_X_DIR false // for Mendel set to false, for Orca set to true
#define INVERT_Y_DIR false // for Mendel set to true, for Orca set to false
#define INVERT_Z_DIR true // for Mendel set to false, for Orca set to true
#define INVERT_E0_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_Z_DIR false // for Mendel set to false, for Orca set to true
#define INVERT_E0_DIR true // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E1_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E2_DIR false // for direct drive extruder v9 set to true, for geared extruder set to false
@ -422,8 +424,8 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
// #define EXTRUDER_OFFSET_Y {0.0, 5.00} // (in mm) for each extruder, offset of the hotend on the Y axis
// The speed change that does not require acceleration (i.e. the software might assume it can be done instantaneously)
#define DEFAULT_XJERK 5.0 // (mm/sec)
#define DEFAULT_YJERK 5.0 // (mm/sec)
#define DEFAULT_XJERK 10.0 // (mm/sec)
#define DEFAULT_YJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.2 // (mm/sec)
#define DEFAULT_EJERK 2.5 // (mm/sec)
@ -459,8 +461,8 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#define SDSUPPORT // Enable SD Card Support in Hardware Console
//#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error)
#define SD_CHECK_AND_RETRY // Use CRC checks and retries on the SD communication
#define ENCODER_PULSES_PER_STEP 2 // Increase if you have a high resolution encoder
#define ENCODER_STEPS_PER_MENU_ITEM 2 // Set according to ENCODER_PULSES_PER_STEP or your liking
#define ENCODER_PULSES_PER_STEP 4 // Increase if you have a high resolution encoder
#define ENCODER_STEPS_PER_MENU_ITEM 1 // Set according to ENCODER_PULSES_PER_STEP or your liking
//#define ULTIMAKERCONTROLLER //as available from the Ultimaker online store.
//#define ULTIPANEL //the UltiPanel as on Thingiverse
//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 // this is the tone frequency the buzzer plays when on UI feedback. ie Screen Click

View file

@ -22,5 +22,6 @@ FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_Prin
inline uint8_t calibration_status() { return eeprom_read_byte((uint8_t*)EEPROM_CALIBRATION_STATUS); }
inline uint8_t calibration_status_store(uint8_t status) { eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS, status); }
inline bool calibration_status_pinda() { return eeprom_read_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA); }
#endif//CONFIG_STORE_H

View file

@ -282,8 +282,10 @@ extern float retract_recover_length, retract_recover_length_swap, retract_recove
extern unsigned long starttime;
extern unsigned long stoptime;
extern int bowden_length[4];
extern bool is_usb_printing;
extern bool homing_flag;
extern bool temp_cal_active;
extern bool loading_flag;
extern unsigned int usb_printing_counter;
@ -297,12 +299,13 @@ extern unsigned int heating_status_counter;
extern bool custom_message;
extern unsigned int custom_message_type;
extern unsigned int custom_message_state;
extern char snmm_filaments_used;
extern unsigned long PingTime;
extern bool fan_state[2];
extern int fan_edge_counter[2];
extern int fan_speed[2];
// Handling multiple extruders pins
extern uint8_t active_extruder;
@ -313,18 +316,30 @@ extern void digipot_i2c_init();
#endif
//Long pause
extern int saved_feedmultiply;
extern float HotendTempBckp;
extern int fanSpeedBckp;
extern float pause_lastpos[4];
extern unsigned long pause_time;
extern unsigned long start_pause_print;
extern bool mesh_bed_leveling_flag;
extern bool mesh_bed_run_from_menu;
extern float distance_from_min[3];
extern float angleDiff;
extern void calculate_volumetric_multipliers();
// Similar to the default Arduino delay function,
// but it keeps the background tasks running.
extern void delay_keep_alive(int ms);
extern void delay_keep_alive(unsigned int ms);
extern void check_babystep();
extern void long_pause();
#ifdef DIS
void d_setup();
@ -332,3 +347,8 @@ float d_ReadData();
void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_points_num, float shift_x, float shift_y);
#endif
float temp_comp_interpolation(float temperature);
void temp_compensation_apply();
void temp_compensation_start();
void wait_for_heater(long codenum);
void serialecho_temperatures();

File diff suppressed because it is too large Load diff

View file

@ -31,7 +31,7 @@
#include "SdVolume.h"
//------------------------------------------------------------------------------
/**
* \struct fpos_t
* \struct filepos_t
* \brief internal type for istream
* do not use in user apps
*/

View file

@ -180,6 +180,7 @@ print $fh <<END
#ifndef LANGUAGE_ALL_H
#define LANGUAGE_ALL_H
#include <avr/pgmspace.h>
// Language indices into their particular symbol tables.
END
;
@ -242,7 +243,7 @@ $filename = 'language_all.cpp';
open($fh, '>', $filename) or die "Could not open file '$filename' $!";
print $fh <<'END'
#include <avr/pgmspace.h>
#include "Configuration_prusa.h"
#include "language_all.h"

File diff suppressed because it is too large Load diff

View file

@ -1,6 +1,7 @@
#ifndef LANGUAGE_ALL_H
#define LANGUAGE_ALL_H
#include <avr/pgmspace.h>
// Language indices into their particular symbol tables.
#define LANG_ID_EN 0
#define LANG_ID_CZ 1
@ -29,6 +30,8 @@ extern const char* const MSG_ACTIVE_EXTRUDER_LANG_TABLE[1];
#define MSG_ACTIVE_EXTRUDER LANG_TABLE_SELECT_EXPLICIT(MSG_ACTIVE_EXTRUDER_LANG_TABLE, 0)
extern const char* const MSG_ADJUSTZ_LANG_TABLE[LANG_NUM];
#define MSG_ADJUSTZ LANG_TABLE_SELECT(MSG_ADJUSTZ_LANG_TABLE)
extern const char* const MSG_ALL_LANG_TABLE[LANG_NUM];
#define MSG_ALL LANG_TABLE_SELECT(MSG_ALL_LANG_TABLE)
extern const char* const MSG_AMAX_LANG_TABLE[1];
#define MSG_AMAX LANG_TABLE_SELECT_EXPLICIT(MSG_AMAX_LANG_TABLE, 0)
extern const char* const MSG_AUTHOR_LANG_TABLE[1];
@ -61,8 +64,8 @@ extern const char* const MSG_BED_CORRECTION_MENU_LANG_TABLE[LANG_NUM];
#define MSG_BED_CORRECTION_MENU LANG_TABLE_SELECT(MSG_BED_CORRECTION_MENU_LANG_TABLE)
extern const char* const MSG_BED_CORRECTION_REAR_LANG_TABLE[LANG_NUM];
#define MSG_BED_CORRECTION_REAR LANG_TABLE_SELECT(MSG_BED_CORRECTION_REAR_LANG_TABLE)
extern const char* const MSG_BED_CORRECTION_RESET_LANG_TABLE[1];
#define MSG_BED_CORRECTION_RESET LANG_TABLE_SELECT_EXPLICIT(MSG_BED_CORRECTION_RESET_LANG_TABLE, 0)
extern const char* const MSG_BED_CORRECTION_RESET_LANG_TABLE[LANG_NUM];
#define MSG_BED_CORRECTION_RESET LANG_TABLE_SELECT(MSG_BED_CORRECTION_RESET_LANG_TABLE)
extern const char* const MSG_BED_CORRECTION_RIGHT_LANG_TABLE[LANG_NUM];
#define MSG_BED_CORRECTION_RIGHT LANG_TABLE_SELECT(MSG_BED_CORRECTION_RIGHT_LANG_TABLE)
extern const char* const MSG_BED_DONE_LANG_TABLE[LANG_NUM];
@ -107,6 +110,10 @@ extern const char* const MSG_CALIBRATE_BED_RESET_LANG_TABLE[LANG_NUM];
#define MSG_CALIBRATE_BED_RESET LANG_TABLE_SELECT(MSG_CALIBRATE_BED_RESET_LANG_TABLE)
extern const char* const MSG_CALIBRATE_E_LANG_TABLE[LANG_NUM];
#define MSG_CALIBRATE_E LANG_TABLE_SELECT(MSG_CALIBRATE_E_LANG_TABLE)
extern const char* const MSG_CALIBRATE_PINDA_LANG_TABLE[LANG_NUM];
#define MSG_CALIBRATE_PINDA LANG_TABLE_SELECT(MSG_CALIBRATE_PINDA_LANG_TABLE)
extern const char* const MSG_CALIBRATION_PINDA_MENU_LANG_TABLE[LANG_NUM];
#define MSG_CALIBRATION_PINDA_MENU LANG_TABLE_SELECT(MSG_CALIBRATION_PINDA_MENU_LANG_TABLE)
extern const char* const MSG_CARD_MENU_LANG_TABLE[LANG_NUM];
#define MSG_CARD_MENU LANG_TABLE_SELECT(MSG_CARD_MENU_LANG_TABLE)
extern const char* const MSG_CHANGE_EXTR_LANG_TABLE[LANG_NUM];
@ -115,6 +122,8 @@ extern const char* const MSG_CHANGE_SUCCESS_LANG_TABLE[LANG_NUM];
#define MSG_CHANGE_SUCCESS LANG_TABLE_SELECT(MSG_CHANGE_SUCCESS_LANG_TABLE)
extern const char* const MSG_CHANGING_FILAMENT_LANG_TABLE[LANG_NUM];
#define MSG_CHANGING_FILAMENT LANG_TABLE_SELECT(MSG_CHANGING_FILAMENT_LANG_TABLE)
extern const char* const MSG_CHOOSE_EXTRUDER_LANG_TABLE[LANG_NUM];
#define MSG_CHOOSE_EXTRUDER LANG_TABLE_SELECT(MSG_CHOOSE_EXTRUDER_LANG_TABLE)
extern const char* const MSG_CLEAN_NOZZLE_E_LANG_TABLE[LANG_NUM];
#define MSG_CLEAN_NOZZLE_E LANG_TABLE_SELECT(MSG_CLEAN_NOZZLE_E_LANG_TABLE)
extern const char* const MSG_CNG_SDCARD_LANG_TABLE[1];
@ -135,6 +144,8 @@ extern const char* const MSG_CORRECTLY_LANG_TABLE[LANG_NUM];
#define MSG_CORRECTLY LANG_TABLE_SELECT(MSG_CORRECTLY_LANG_TABLE)
extern const char* const MSG_COUNT_X_LANG_TABLE[1];
#define MSG_COUNT_X LANG_TABLE_SELECT_EXPLICIT(MSG_COUNT_X_LANG_TABLE, 0)
extern const char* const MSG_CURRENT_LANG_TABLE[LANG_NUM];
#define MSG_CURRENT LANG_TABLE_SELECT(MSG_CURRENT_LANG_TABLE)
extern const char* const MSG_DISABLE_STEPPERS_LANG_TABLE[LANG_NUM];
#define MSG_DISABLE_STEPPERS LANG_TABLE_SELECT(MSG_DISABLE_STEPPERS_LANG_TABLE)
extern const char* const MSG_DWELL_LANG_TABLE[LANG_NUM];
@ -169,6 +180,16 @@ extern const char* const MSG_ERR_STOPPED_LANG_TABLE[1];
#define MSG_ERR_STOPPED LANG_TABLE_SELECT_EXPLICIT(MSG_ERR_STOPPED_LANG_TABLE, 0)
extern const char* const MSG_EXTERNAL_RESET_LANG_TABLE[1];
#define MSG_EXTERNAL_RESET LANG_TABLE_SELECT_EXPLICIT(MSG_EXTERNAL_RESET_LANG_TABLE, 0)
extern const char* const MSG_EXTRUDER_LANG_TABLE[LANG_NUM];
#define MSG_EXTRUDER LANG_TABLE_SELECT(MSG_EXTRUDER_LANG_TABLE)
extern const char* const MSG_EXTRUDER_1_LANG_TABLE[LANG_NUM];
#define MSG_EXTRUDER_1 LANG_TABLE_SELECT(MSG_EXTRUDER_1_LANG_TABLE)
extern const char* const MSG_EXTRUDER_2_LANG_TABLE[LANG_NUM];
#define MSG_EXTRUDER_2 LANG_TABLE_SELECT(MSG_EXTRUDER_2_LANG_TABLE)
extern const char* const MSG_EXTRUDER_3_LANG_TABLE[LANG_NUM];
#define MSG_EXTRUDER_3 LANG_TABLE_SELECT(MSG_EXTRUDER_3_LANG_TABLE)
extern const char* const MSG_EXTRUDER_4_LANG_TABLE[LANG_NUM];
#define MSG_EXTRUDER_4 LANG_TABLE_SELECT(MSG_EXTRUDER_4_LANG_TABLE)
extern const char* const MSG_E_CAL_KNOB_LANG_TABLE[LANG_NUM];
#define MSG_E_CAL_KNOB LANG_TABLE_SELECT(MSG_E_CAL_KNOB_LANG_TABLE)
extern const char* const MSG_Enqueing_LANG_TABLE[1];
@ -197,14 +218,14 @@ extern const char* const MSG_FILE_SAVED_LANG_TABLE[1];
#define MSG_FILE_SAVED LANG_TABLE_SELECT_EXPLICIT(MSG_FILE_SAVED_LANG_TABLE, 0)
extern const char* const MSG_FIL_ADJUSTING_LANG_TABLE[LANG_NUM];
#define MSG_FIL_ADJUSTING LANG_TABLE_SELECT(MSG_FIL_ADJUSTING_LANG_TABLE)
extern const char* const MSG_FIL_LOADED_CHECK_LANG_TABLE[LANG_NUM];
#define MSG_FIL_LOADED_CHECK LANG_TABLE_SELECT(MSG_FIL_LOADED_CHECK_LANG_TABLE)
extern const char* const MSG_FIL_TUNING_LANG_TABLE[LANG_NUM];
#define MSG_FIL_TUNING LANG_TABLE_SELECT(MSG_FIL_TUNING_LANG_TABLE)
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_LANG_TABLE[LANG_NUM];
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION LANG_TABLE_SELECT(MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION_LANG_TABLE)
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_LANG_TABLE[LANG_NUM];
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 LANG_TABLE_SELECT(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1_LANG_TABLE)
extern const char* const MSG_FIND_BED_OFFSET_AND_SKEW_LINE2_LANG_TABLE[LANG_NUM];
#define MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 LANG_TABLE_SELECT(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2_LANG_TABLE)
extern const char* const MSG_FINISHING_MOVEMENTS_LANG_TABLE[LANG_NUM];
#define MSG_FINISHING_MOVEMENTS LANG_TABLE_SELECT(MSG_FINISHING_MOVEMENTS_LANG_TABLE)
extern const char* const MSG_FLOW_LANG_TABLE[LANG_NUM];
#define MSG_FLOW LANG_TABLE_SELECT(MSG_FLOW_LANG_TABLE)
extern const char* const MSG_FLOW0_LANG_TABLE[1];
@ -251,10 +272,20 @@ extern const char* const MSG_LOADING_COLOR_LANG_TABLE[LANG_NUM];
#define MSG_LOADING_COLOR LANG_TABLE_SELECT(MSG_LOADING_COLOR_LANG_TABLE)
extern const char* const MSG_LOADING_FILAMENT_LANG_TABLE[LANG_NUM];
#define MSG_LOADING_FILAMENT LANG_TABLE_SELECT(MSG_LOADING_FILAMENT_LANG_TABLE)
extern const char* const MSG_LOAD_ALL_LANG_TABLE[LANG_NUM];
#define MSG_LOAD_ALL LANG_TABLE_SELECT(MSG_LOAD_ALL_LANG_TABLE)
extern const char* const MSG_LOAD_EPROM_LANG_TABLE[1];
#define MSG_LOAD_EPROM LANG_TABLE_SELECT_EXPLICIT(MSG_LOAD_EPROM_LANG_TABLE, 0)
extern const char* const MSG_LOAD_FILAMENT_LANG_TABLE[LANG_NUM];
#define MSG_LOAD_FILAMENT LANG_TABLE_SELECT(MSG_LOAD_FILAMENT_LANG_TABLE)
extern const char* const MSG_LOAD_FILAMENT_1_LANG_TABLE[LANG_NUM];
#define MSG_LOAD_FILAMENT_1 LANG_TABLE_SELECT(MSG_LOAD_FILAMENT_1_LANG_TABLE)
extern const char* const MSG_LOAD_FILAMENT_2_LANG_TABLE[LANG_NUM];
#define MSG_LOAD_FILAMENT_2 LANG_TABLE_SELECT(MSG_LOAD_FILAMENT_2_LANG_TABLE)
extern const char* const MSG_LOAD_FILAMENT_3_LANG_TABLE[LANG_NUM];
#define MSG_LOAD_FILAMENT_3 LANG_TABLE_SELECT(MSG_LOAD_FILAMENT_3_LANG_TABLE)
extern const char* const MSG_LOAD_FILAMENT_4_LANG_TABLE[LANG_NUM];
#define MSG_LOAD_FILAMENT_4 LANG_TABLE_SELECT(MSG_LOAD_FILAMENT_4_LANG_TABLE)
extern const char* const MSG_LOOSE_PULLEY_LANG_TABLE[LANG_NUM];
#define MSG_LOOSE_PULLEY LANG_TABLE_SELECT(MSG_LOOSE_PULLEY_LANG_TABLE)
extern const char* const MSG_M104_INVALID_EXTRUDER_LANG_TABLE[1];
@ -343,6 +374,16 @@ extern const char* const MSG_PAUSE_PRINT_LANG_TABLE[LANG_NUM];
#define MSG_PAUSE_PRINT LANG_TABLE_SELECT(MSG_PAUSE_PRINT_LANG_TABLE)
extern const char* const MSG_PICK_Z_LANG_TABLE[LANG_NUM];
#define MSG_PICK_Z LANG_TABLE_SELECT(MSG_PICK_Z_LANG_TABLE)
extern const char* const MSG_PID_EXTRUDER_LANG_TABLE[LANG_NUM];
#define MSG_PID_EXTRUDER LANG_TABLE_SELECT(MSG_PID_EXTRUDER_LANG_TABLE)
extern const char* const MSG_PID_FINISHED_LANG_TABLE[LANG_NUM];
#define MSG_PID_FINISHED LANG_TABLE_SELECT(MSG_PID_FINISHED_LANG_TABLE)
extern const char* const MSG_PID_RUNNING_LANG_TABLE[LANG_NUM];
#define MSG_PID_RUNNING LANG_TABLE_SELECT(MSG_PID_RUNNING_LANG_TABLE)
extern const char* const MSG_PINDA_NOT_CALIBRATED_LANG_TABLE[LANG_NUM];
#define MSG_PINDA_NOT_CALIBRATED LANG_TABLE_SELECT(MSG_PINDA_NOT_CALIBRATED_LANG_TABLE)
extern const char* const MSG_PINDA_PREHEAT_LANG_TABLE[LANG_NUM];
#define MSG_PINDA_PREHEAT LANG_TABLE_SELECT(MSG_PINDA_PREHEAT_LANG_TABLE)
extern const char* const MSG_PLANNER_BUFFER_BYTES_LANG_TABLE[1];
#define MSG_PLANNER_BUFFER_BYTES LANG_TABLE_SELECT_EXPLICIT(MSG_PLANNER_BUFFER_BYTES_LANG_TABLE, 0)
extern const char* const MSG_PLEASE_WAIT_LANG_TABLE[LANG_NUM];
@ -355,12 +396,16 @@ extern const char* const MSG_PREHEAT_LANG_TABLE[LANG_NUM];
#define MSG_PREHEAT LANG_TABLE_SELECT(MSG_PREHEAT_LANG_TABLE)
extern const char* const MSG_PREHEAT_NOZZLE_LANG_TABLE[LANG_NUM];
#define MSG_PREHEAT_NOZZLE LANG_TABLE_SELECT(MSG_PREHEAT_NOZZLE_LANG_TABLE)
extern const char* const MSG_PREPARE_FILAMENT_LANG_TABLE[LANG_NUM];
#define MSG_PREPARE_FILAMENT LANG_TABLE_SELECT(MSG_PREPARE_FILAMENT_LANG_TABLE)
extern const char* const MSG_PRESS_LANG_TABLE[LANG_NUM];
#define MSG_PRESS LANG_TABLE_SELECT(MSG_PRESS_LANG_TABLE)
extern const char* const MSG_PRINTER_DISCONNECTED_LANG_TABLE[1];
#define MSG_PRINTER_DISCONNECTED LANG_TABLE_SELECT_EXPLICIT(MSG_PRINTER_DISCONNECTED_LANG_TABLE, 0)
extern const char* const MSG_PRINT_ABORTED_LANG_TABLE[LANG_NUM];
#define MSG_PRINT_ABORTED LANG_TABLE_SELECT(MSG_PRINT_ABORTED_LANG_TABLE)
extern const char* const MSG_PRINT_PAUSED_LANG_TABLE[LANG_NUM];
#define MSG_PRINT_PAUSED LANG_TABLE_SELECT(MSG_PRINT_PAUSED_LANG_TABLE)
extern const char* const MSG_PRUSA3D_LANG_TABLE[LANG_NUM];
#define MSG_PRUSA3D LANG_TABLE_SELECT(MSG_PRUSA3D_LANG_TABLE)
extern const char* const MSG_PRUSA3D_FORUM_LANG_TABLE[LANG_NUM];
@ -383,6 +428,8 @@ extern const char* const MSG_RESUME_PRINT_LANG_TABLE[LANG_NUM];
#define MSG_RESUME_PRINT LANG_TABLE_SELECT(MSG_RESUME_PRINT_LANG_TABLE)
extern const char* const MSG_RESUMING_LANG_TABLE[LANG_NUM];
#define MSG_RESUMING LANG_TABLE_SELECT(MSG_RESUMING_LANG_TABLE)
extern const char* const MSG_RESUMING_PRINT_LANG_TABLE[LANG_NUM];
#define MSG_RESUMING_PRINT LANG_TABLE_SELECT(MSG_RESUMING_PRINT_LANG_TABLE)
extern const char* const MSG_SD_CANT_ENTER_SUBDIR_LANG_TABLE[1];
#define MSG_SD_CANT_ENTER_SUBDIR LANG_TABLE_SELECT_EXPLICIT(MSG_SD_CANT_ENTER_SUBDIR_LANG_TABLE, 0)
extern const char* const MSG_SD_CANT_OPEN_SUBDIR_LANG_TABLE[1];
@ -477,6 +524,8 @@ extern const char* const MSG_SET_HOME_OFFSETS_LANG_TABLE[1];
#define MSG_SET_HOME_OFFSETS LANG_TABLE_SELECT_EXPLICIT(MSG_SET_HOME_OFFSETS_LANG_TABLE, 0)
extern const char* const MSG_SET_ORIGIN_LANG_TABLE[1];
#define MSG_SET_ORIGIN LANG_TABLE_SELECT_EXPLICIT(MSG_SET_ORIGIN_LANG_TABLE, 0)
extern const char* const MSG_SET_TEMPERATURE_LANG_TABLE[LANG_NUM];
#define MSG_SET_TEMPERATURE LANG_TABLE_SELECT(MSG_SET_TEMPERATURE_LANG_TABLE)
extern const char* const MSG_SHOW_END_STOPS_LANG_TABLE[LANG_NUM];
#define MSG_SHOW_END_STOPS LANG_TABLE_SELECT(MSG_SHOW_END_STOPS_LANG_TABLE)
extern const char* const MSG_SILENT_MODE_OFF_LANG_TABLE[LANG_NUM];
@ -517,6 +566,14 @@ extern const char* const MSG_TAKE_EFFECT_LANG_TABLE[LANG_NUM];
#define MSG_TAKE_EFFECT LANG_TABLE_SELECT(MSG_TAKE_EFFECT_LANG_TABLE)
extern const char* const MSG_TEMPERATURE_LANG_TABLE[LANG_NUM];
#define MSG_TEMPERATURE LANG_TABLE_SELECT(MSG_TEMPERATURE_LANG_TABLE)
extern const char* const MSG_TEMP_CALIBRATION_LANG_TABLE[LANG_NUM];
#define MSG_TEMP_CALIBRATION LANG_TABLE_SELECT(MSG_TEMP_CALIBRATION_LANG_TABLE)
extern const char* const MSG_TEMP_CALIBRATION_DONE_LANG_TABLE[LANG_NUM];
#define MSG_TEMP_CALIBRATION_DONE LANG_TABLE_SELECT(MSG_TEMP_CALIBRATION_DONE_LANG_TABLE)
extern const char* const MSG_TEMP_CALIBRATION_OFF_LANG_TABLE[LANG_NUM];
#define MSG_TEMP_CALIBRATION_OFF LANG_TABLE_SELECT(MSG_TEMP_CALIBRATION_OFF_LANG_TABLE)
extern const char* const MSG_TEMP_CALIBRATION_ON_LANG_TABLE[LANG_NUM];
#define MSG_TEMP_CALIBRATION_ON LANG_TABLE_SELECT(MSG_TEMP_CALIBRATION_ON_LANG_TABLE)
extern const char* const MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF_LANG_TABLE[LANG_NUM];
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF LANG_TABLE_SELECT(MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF_LANG_TABLE)
extern const char* const MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON_LANG_TABLE[LANG_NUM];
@ -527,10 +584,22 @@ extern const char* const MSG_UNKNOWN_COMMAND_LANG_TABLE[1];
#define MSG_UNKNOWN_COMMAND LANG_TABLE_SELECT_EXPLICIT(MSG_UNKNOWN_COMMAND_LANG_TABLE, 0)
extern const char* const MSG_UNLOADING_FILAMENT_LANG_TABLE[LANG_NUM];
#define MSG_UNLOADING_FILAMENT LANG_TABLE_SELECT(MSG_UNLOADING_FILAMENT_LANG_TABLE)
extern const char* const MSG_UNLOAD_ALL_LANG_TABLE[LANG_NUM];
#define MSG_UNLOAD_ALL LANG_TABLE_SELECT(MSG_UNLOAD_ALL_LANG_TABLE)
extern const char* const MSG_UNLOAD_FILAMENT_LANG_TABLE[LANG_NUM];
#define MSG_UNLOAD_FILAMENT LANG_TABLE_SELECT(MSG_UNLOAD_FILAMENT_LANG_TABLE)
extern const char* const MSG_UNLOAD_FILAMENT_1_LANG_TABLE[LANG_NUM];
#define MSG_UNLOAD_FILAMENT_1 LANG_TABLE_SELECT(MSG_UNLOAD_FILAMENT_1_LANG_TABLE)
extern const char* const MSG_UNLOAD_FILAMENT_2_LANG_TABLE[LANG_NUM];
#define MSG_UNLOAD_FILAMENT_2 LANG_TABLE_SELECT(MSG_UNLOAD_FILAMENT_2_LANG_TABLE)
extern const char* const MSG_UNLOAD_FILAMENT_3_LANG_TABLE[LANG_NUM];
#define MSG_UNLOAD_FILAMENT_3 LANG_TABLE_SELECT(MSG_UNLOAD_FILAMENT_3_LANG_TABLE)
extern const char* const MSG_UNLOAD_FILAMENT_4_LANG_TABLE[LANG_NUM];
#define MSG_UNLOAD_FILAMENT_4 LANG_TABLE_SELECT(MSG_UNLOAD_FILAMENT_4_LANG_TABLE)
extern const char* const MSG_USB_PRINTING_LANG_TABLE[LANG_NUM];
#define MSG_USB_PRINTING LANG_TABLE_SELECT(MSG_USB_PRINTING_LANG_TABLE)
extern const char* const MSG_USED_LANG_TABLE[LANG_NUM];
#define MSG_USED LANG_TABLE_SELECT(MSG_USED_LANG_TABLE)
extern const char* const MSG_USERWAIT_LANG_TABLE[LANG_NUM];
#define MSG_USERWAIT LANG_TABLE_SELECT(MSG_USERWAIT_LANG_TABLE)
extern const char* const MSG_VMIN_LANG_TABLE[1];

View file

@ -74,6 +74,16 @@
#define MSG_PREHEAT "Predehrev"
#define MSG_UNLOAD_FILAMENT "Vyjmout filament"
#define MSG_LOAD_FILAMENT "Zavest filament"
#define MSG_LOAD_FILAMENT_1 "Zavest filament 1"
#define MSG_LOAD_FILAMENT_2 "Zavest filament 2"
#define MSG_LOAD_FILAMENT_3 "Zavest filament 3"
#define MSG_LOAD_FILAMENT_4 "Zavest filament 4"
#define MSG_UNLOAD_FILAMENT_1 "Vyjmout filam. 1"
#define MSG_UNLOAD_FILAMENT_2 "Vyjmout filam. 2"
#define MSG_UNLOAD_FILAMENT_3 "Vyjmout filam. 3"
#define MSG_UNLOAD_FILAMENT_4 "Vyjmout filam. 4"
#define MSG_UNLOAD_ALL "Vyjmout vse"
#define MSG_LOAD_ALL "Zavest vse"
#define MSG_RECTRACT "Rectract"
#define MSG_ERROR "CHYBA:"
@ -212,6 +222,7 @@
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " z 9"
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Merim referencni vysku kalibracniho bodu"
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " z 9"
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iterace "
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Kalibrace XYZ selhala. Kalibracni bod podlozky nenalezen."
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Kalibrace XYZ selhala. Nahlednete do manualu."
@ -247,13 +258,12 @@
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
#define MSG_LOOSE_PULLEY "Uvolnena remenicka"
#define MSG_FILAMENT_LOADING_T0 "Vložte filament do extruderu 1. Potvrdte tlacitkem."
#define MSG_FILAMENT_LOADING_T1 "Vložte filament do extruderu 2. Potvrdte tlacitkem."
#define MSG_FILAMENT_LOADING_T2 "Vložte filament do extruderu 3. Potvrdte tlacitkem."
#define MSG_FILAMENT_LOADING_T3 "Vložte filament do extruderu 4. Potvrdte tlacitkem."
#define MSG_FILAMENT_LOADING_T0 "Vlozte filament do extruderu 1. Potvrdte tlacitkem."
#define MSG_FILAMENT_LOADING_T1 "Vlozte filament do extruderu 2. Potvrdte tlacitkem."
#define MSG_FILAMENT_LOADING_T2 "Vlozte filament do extruderu 3. Potvrdte tlacitkem."
#define MSG_FILAMENT_LOADING_T3 "Vlozte filament do extruderu 4. Potvrdte tlacitkem."
#define MSG_CHANGE_EXTR "Zmenit extruder"
#define MSG_FIL_LOADED_CHECK "Je filament zaveden?"
#define MSG_FIL_TUNING "Otacenim tlacitka doladte pozici filamentu."
#define MSG_FIL_ADJUSTING "Probiha srovnani filamentu. Prosim cekejte."
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamenty jsou srovnany. Pro uspesnou kalibraci prosim ocistete trysku. Po te potvrdte tlacitkem."
#define MSG_CALIBRATE_E "Kalibrovat E"
@ -265,3 +275,30 @@
#define MSG_UNLOADING_FILAMENT "Vysouvam filament"
#define MSG_PAPER "Umistete list papiru na podlozku a udrzujte jej pod tryskou behem mereni prvnich 4 bodu. Pokud tryska zachyti papir, vypnete tiskarnu."
#define MSG_FINISHING_MOVEMENTS "Dokoncovani pohybu"
#define MSG_PRINT_PAUSED "Tisk pozastaven"
#define MSG_RESUMING_PRINT "Obnovovani tisku"
#define MSG_PID_EXTRUDER "PID kalibrace"
#define MSG_SET_TEMPERATURE "Nastavte teplotu:"
#define MSG_PID_FINISHED "PID kal. ukoncena"
#define MSG_PID_RUNNING "PID kal. "
#define MSG_CALIBRATE_PINDA "Zkalibrovat"
#define MSG_CALIBRATION_PINDA_MENU "Teplot. kalibrace"
#define MSG_PINDA_NOT_CALIBRATED "Tiskarna nebyla teplotne zkalibrovana"
#define MSG_PINDA_PREHEAT "Nahrivani PINDA"
#define MSG_TEMP_CALIBRATION "Tepl. kal. "
#define MSG_TEMP_CALIBRATION_DONE "Teplotni kalibrace dokoncena. Pokracujte stiskem tlacitka."
#define MSG_TEMP_CALIBRATION_ON "Tepl. kal. [ON]"
#define MSG_TEMP_CALIBRATION_OFF "Tepl. kal. [OFF]"
#define MSG_PREPARE_FILAMENT "Pripravte filament"
#define MSG_ALL "Vse"
#define MSG_USED "Pouzite behem tisku"
#define MSG_CURRENT "Pouze aktualni"
#define MSG_CHOOSE_EXTRUDER "Vyberte extruder:"
#define MSG_EXTRUDER "Extruder"
#define MSG_EXTRUDER_1 "Extruder 1"
#define MSG_EXTRUDER_2 "Extruder 2"
#define MSG_EXTRUDER_3 "Extruder 3"
#define MSG_EXTRUDER_4 "Extruder 4"

317
Firmware/language_de.h Normal file
View file

@ -0,0 +1,317 @@
+/**
+ * German
+ *
+ * LCD Menu Messages
+ * Please note these are limited to 17 characters!
+ *
+ */
+
+#define(length = 20) WELCOME_MSG CUSTOM_MENDEL_NAME " bereit."
+ #define MSG_SD_INSERTED "SD eingesetzt"
+ #define MSG_SD_REMOVED "SD entfernt "
+ #define MSG_MAIN "Hauptmenue"
+ #define MSG_DISABLE_STEPPERS "Motoren aus"
+ #define MSG_AUTO_HOME "Startposition"
+ #define MSG_SET_HOME_OFFSETS "Abstand vom Ursprung einstellen"
+ #define MSG_SET_ORIGIN "Ursprung einstellen"
+ #define MSG_COOLDOWN "Abkuehlen"
+ #define MSG_SWITCH_PS_ON "Netzteil EIN"
+ #define MSG_SWITCH_PS_OFF "Netzteil AUS"
+ #define MSG_MOVE_AXIS "Achsbewegung"
+ #define MSG_MOVE_X "Bewege X"
+ #define MSG_MOVE_Y "Bewege Y"
+ #define MSG_MOVE_Z "Bewege Z"
+ #define MSG_MOVE_E "Extruder"
+ #define MSG_SPEED "Geschwindigkeit"
+ #define MSG_NOZZLE "Duese"
+ #define MSG_NOZZLE1 "Duese2"
+ #define MSG_NOZZLE2 "Duese3"
+ #define MSG_BED "Bed"
+ #define MSG_FAN_SPEED "Luefter-Tempo"
+ #define MSG_FLOW "Durchfluss"
+ #define MSG_FLOW0 "Durchfluss 0"
+ #define MSG_FLOW1 "Durchfluss 1"
+ #define MSG_FLOW2 "Durchfluss 2"
+ #define MSG_CONTROL "Kontrolle"
+ #define MSG_MIN " \002 Min"
+ #define MSG_MAX " \002 Max"
+ #define MSG_FACTOR " \002 Fakt"
+ #define MSG_TEMPERATURE "Temperatur"
+ #define MSG_MOTION "Bewegung"
+ #define MSG_VOLUMETRIC "Filament"
+ #define MSG_VOLUMETRIC_ENABLED "E in mm3"
+ #define MSG_STORE_EPROM "Abspeichern"
+ #define MSG_LOAD_EPROM "Lade Speicher"
+ #define MSG_RESTORE_FAILSAFE "Standardwerte setzen"
+ #define MSG_REFRESH "\xF8" "Erneuern"
+ #define MSG_WATCH "Information"
+ #define MSG_TUNE "Feineinstellung"
+ #define MSG_PAUSE_PRINT "Druck unterbrech."
+ #define MSG_RESUME_PRINT "Fortsetzen"
+ #define MSG_STOP_PRINT "Druck abbrechen"
+ #define MSG_CARD_MENU "Drucken von SD"
+ #define MSG_NO_CARD "Keine SD Karte"
+ #define MSG_DWELL "Einen Moment bitte."
+ #define MSG_USERWAIT "Warte auf user..."
+ #define MSG_RESUMING "Druck fortgesetzt"
+ #define(length = 20) MSG_PRINT_ABORTED "Druck abgebrochen"
+ #define MSG_NO_MOVE "Keine Bewegung."
+ #define MSG_KILLED "ABGEBROCHEN. "
+ #define MSG_STOPPED "GESTOPPT. "
+ #define MSG_FILAMENTCHANGE "Filament-Wechsel"
+ #define MSG_INIT_SDCARD "Init SD Karte"
+ #define MSG_CNG_SDCARD "Wechsel SD Karte"
+ #define MSG_BABYSTEP_X "Babystep X"
+ #define MSG_BABYSTEP_Y "Babystep Y"
+ #define MSG_BABYSTEP_Z "Z einstellen"
+ #define MSG_ADJUSTZ "Auto Z einstellen?"
+ #define MSG_PICK_Z "Waehle Abdruck"
+
+#define MSG_SETTINGS "Einstellungen"
+ #define MSG_PREHEAT "Vorwaermen"
+ #define MSG_UNLOAD_FILAMENT "Filament entladen"
+ #define MSG_LOAD_FILAMENT "Filament laden"
+
+#define MSG_RECTRACT "Retract"
+ #define MSG_ERROR "FEHLER:"
+ #define(length = 20) MSG_PREHEAT_NOZZLE "Duese Vorwaermen"
+ #define MSG_SUPPORT "Support"
+ #define(length = 20) MSG_CORRECTLY "Wechsel ok?"
+ #define MSG_YES "Ja"
+ #define MSG_NO "Nein"
+ #define(length = 19) MSG_NOT_LOADED "Fil. nicht geladen"
+ #define MSG_NOT_COLOR "Farbe unklar"
+ #define(length = 20) MSG_LOADING_FILAMENT "Filament leadt"
+ #define(length = 20) MSG_PLEASE_WAIT "Bitte warten"
+ #define MSG_LOADING_COLOR "Lade Farbe"
+ #define MSG_CHANGE_SUCCESS "Wechsel erfolgr.!"
+ #define(length = 20) MSG_PRESS "und Knopf druecken"
+ #define(length = 20) MSG_INSERT_FILAMENT "Filament einlegen"
+ #define(length = 20) MSG_CHANGING_FILAMENT "Filament-Wechsel!"
+
+
+#define MSG_SILENT_MODE_ON "Mode [leise]"
+ #define MSG_SILENT_MODE_OFF "Mode [Hohe Leist]"
+ #define(length = 20) MSG_REBOOT "Zum Uebernehmen "
+ #define(length = 22) MSG_TAKE_EFFECT "Drucker neu starten"
+
+#define MSG_Enqueing "enqueuing \"
+ #define MSG_POWERUP "Einschalten"
+ #define MSG_CONFIGURATION_VER " Letztes Update:"
+ #define MSG_FREE_MEMORY " Freier Speicher: "
+ #define MSG_PLANNER_BUFFER_BYTES " PlannerBufferBytes: "
+ #define MSG_OK "ok"
+ #define MSG_ERR_CHECKSUM_MISMATCH "Pruefsummenfehler, Letzte Zeile: " //Checksum Fehler, Letzte Zeile: "
+ #define MSG_ERR_NO_CHECKSUM "Keine Pruefsumme mit Zeilennummer, Letzte Zeile: " //Keine Checksum mit Zeilennummer, Letzte Zeile: "
+ #define MSG_BEGIN_FILE_LIST "Beginn Dateiliste"
+ #define MSG_END_FILE_LIST "Ende Dateiliste"
+ #define MSG_M104_INVALID_EXTRUDER "M104 Falscher Extruder"
+ #define MSG_M105_INVALID_EXTRUDER "M105 Falscher Extruder"
+ #define MSG_M200_INVALID_EXTRUDER "M200 Falscher Extruder"
+ #define MSG_M218_INVALID_EXTRUDER "M218 Falscher Extruder"
+ #define MSG_M221_INVALID_EXTRUDER "M221 Falscher Extruder"
+ #define MSG_ERR_NO_THERMISTORS "Keine Thermistoren - keine Temperatur"
+ #define MSG_M109_INVALID_EXTRUDER "M109 Falscher Extruder"
+ #define MSG_HEATING "Aufwaermen"
+ #define(length = 20) MSG_HEATING_COMPLETE "Aufwaermen OK"
+ #define MSG_BED_HEATING "Bed aufwaermen"
+ #define MSG_BED_DONE "Bed OK"
+ #define MSG_M115_REPORT "FIRMWARE_NAME:Marlin V1.0.2; Sprinter/grbl mashup for gen6 FIRMWARE_URL:" FIRMWARE_URL " PROTOCOL_VERSION:" PROTOCOL_VERSION " MACHINE_TYPE:" CUSTOM_MENDEL_NAME " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " UUID:" MACHINE_UUID "\n"
+ #define MSG_ERR_KILLED "Printer gestoppt. kill() aufgerufen!"
+ #define MSG_ERR_STOPPED "Drucker aufgrund von Fehlern gestoppt. Fehler beheben und mit M999 neu starten. (Temperatur wird zurueckgesetzt. Nach dem Neustart neu einstellen!)"
+ #define MSG_RESEND "Wiederholen: "
+ #define MSG_M119_REPORT "Statusbericht Endanschlag"
+ #define MSG_ENDSTOP_HIT "AUSGELOEST"
+ #define MSG_ENDSTOP_OPEN "offen"
+
+#define MSG_SD_CANT_OPEN_SUBDIR "Kann Unterverz. nicht oeffnen"
+ #define MSG_SD_INIT_FAIL "SD Init fehlerhaft"
+ #define MSG_SD_VOL_INIT_FAIL "Dateisystem Init fehlerhaft"
+ #define MSG_SD_OPENROOT_FAIL "Zugriff auf Basisverzeichnis misslungen"
+ #define MSG_SD_CARD_OK "SD Karte ok"
+ #define MSG_SD_WORKDIR_FAIL "Oeffnen Arbeitsverzeichnis misslungen"
+ #define MSG_SD_OPEN_FILE_FAIL "Fehler beim Oeffnen der Datei: "
+ #define MSG_SD_FILE_OPENED "Datei geoeffnet: "
+ #define MSG_SD_FILE_SELECTED "Datei ausgewaehlt"
+ #define MSG_SD_WRITE_TO_FILE "Schreiben der Datei: "
+ #define MSG_SD_PRINTING_BYTE "SD printing byte "
+ #define MSG_SD_NOT_PRINTING "Kein SD Print"
+ #define MSG_SD_ERR_WRITE_TO_FILE "Fehler beim Schreiben in Datei"
+ #define MSG_SD_CANT_ENTER_SUBDIR "Zugangsproblem Unterverzeichnis: "
+ #define MSG_STEPPER_TOO_HIGH "Schrittrate zu hoch"
+ #define MSG_ENDSTOPS_HIT "Endanschlag erreicht"
+ #define MSG_ERR_COLD_EXTRUDE_STOP "Stopp, Extruder kalt!"
+ #define MSG_BABYSTEPPING_X "Babystepping X"
+ #define MSG_BABYSTEPPING_Y "Babystepping Y"
+ #define MSG_BABYSTEPPING_Z "Z wurde eingestellt"
+ #define MSG_SERIAL_ERROR_MENU_STRUCTURE "Menuestruktur fehlerhaft"
+
+#define MSG_LANGUAGE_NAME "Deutsch"
+ #define MSG_LANGUAGE_SELECT "Waehle Sprache"
+ #define MSG_PRUSA3D "prusa3d.com"
+ #define MSG_PRUSA3D_FORUM "forum.prusa3d.com"
+ #define MSG_PRUSA3D_HOWTO "howto.prusa3d.com"
+
+#define MSG_SELFTEST_ERROR "Selbtest Fehler!"
+ #define MSG_SELFTEST_PLEASECHECK "Bitte pruefe:"
+ #define MSG_SELFTEST_NOTCONNECTED "Nicht angeschlossen"
+ #define MSG_SELFTEST_HEATERTHERMISTOR "Heater/Thermistor"
+ #define MSG_SELFTEST_BEDHEATER "Bed / Heater"
+ #define MSG_SELFTEST_WIRINGERROR "Verdrahtungfehler"
+ #define MSG_SELFTEST_ENDSTOPS "Endschalter"
+ #define MSG_SELFTEST_MOTOR "Motor"
+ #define MSG_SELFTEST_ENDSTOP "Endstop"
+ #define MSG_SELFTEST_ENDSTOP_NOTHIT "Ende nicht getrof."
+ #define MSG_SELFTEST_OK "Selbsttest OK"
+ #define MSG_LOOSE_PULLEY "Lose Riemenscheibe"
+
+#define MSG_SELFTEST_FAN "Lueftertest"
+#define(length = 20) MSG_SELFTEST_COOLING_FAN "Vorderer Luefter?"
+#define(length = 20) MSG_SELFTEST_EXTRUDER_FAN "Linker Luefter?"
+#define MSG_SELFTEST_FAN_YES "Dreht"
+#define MSG_SELFTEST_FAN_NO "Dreht nicht"
+
+#define(length = 20) MSG_STATS_TOTALFILAMENT "Gesamtfilament:"
+ #define(length = 20) MSG_STATS_TOTALPRINTTIME "Totale Druckzeit:"
+ #define(length = 20) MSG_STATS_FILAMENTUSED "Filamentverbrauch:"
+ #define(length = 20) MSG_STATS_PRINTTIME "Druckzeit: "
+ #define(length = 20) MSG_SELFTEST_START "Selbsttest start "
+ #define(length = 20) MSG_SELFTEST_CHECK_ENDSTOPS "Pruefe Endschalter "
+ #define(length = 20) MSG_SELFTEST_CHECK_HOTEND "Pruefe Hotend"
+ #define(length = 20) MSG_SELFTEST_CHECK_X "Pruefe X Achse "
+ #define(length = 20) MSG_SELFTEST_CHECK_Y "Pruefe Y Achse "
+ #define(length = 20) MSG_SELFTEST_CHECK_Z "Pruefe Z Achse "
+ #define(length = 20) MSG_SELFTEST_CHECK_BED "Pr\x81fe Bed "
+ #define(length = 20) MSG_SELFTEST_CHECK_ALLCORRECT "Alles richtig "
+ #define MSG_SELFTEST "Selbsttest "
+ #define(length = 20) MSG_SELFTEST_FAILED "Selbsttest misslung."
+ #define MSG_STATISTICS "Statistiken "
+ #define MSG_USB_PRINTING "Drucken ueber USB"
+ #define MSG_HOMEYZ "Kalibrieren Z"
+ #define MSG_HOMEYZ_PROGRESS "Kalibriere Z"
+ #define MSG_HOMEYZ_DONE "Kalibrierung OK"
+
+#define MSG_SHOW_END_STOPS "Endschalter Stat."
+ #define MSG_CALIBRATE_BED "Kalibrierung XYZ"
+ #define MSG_CALIBRATE_BED_RESET "Reset XYZ Kalibr."
+
+#define(length = 20, lines = 8) MSG_MOVE_CARRIAGE_TO_THE_TOP "Kalibrieren von XYZ. Drehen Sie den Knopf bis der obere Anschlag erreicht wird. Klicken wenn ganz oben."
+ #define(length = 20, lines = 8) MSG_MOVE_CARRIAGE_TO_THE_TOP_Z "Kalibrieren von Z. Drehen Sie den Knopf bis der obere Anschlag erreicht wird. Klicken wenn ganz oben."
+
+#define(length = 20, lines = 8) MSG_CONFIRM_NOZZLE_CLEAN "Bitte entfernen Sie ueberstehendes Filament von der Duese. Klicken wenn sauber."
+ #define(length = 20, lines = 2) MSG_CONFIRM_CARRIAGE_AT_THE_TOP "Ist der Schlitten ganz oben?"
+
+#define(length = 60) MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 "Suchen Bed Kalibrierpunkt"
+ #define(length = 14) MSG_FIND_BED_OFFSET_AND_SKEW_LINE2 " von 4"
+ #define(length = 60) MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE1 "Verbesserung Bed Kalibrierpunkt"
+ #define(length = 14) MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " von 9"
+ #define(length = 60) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Messen der Referenzhoehe des Kalibrierpunktes"
+ #define(length = 14) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " von 9"
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteration "
+
+#define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "XYZ-Kalibrierung fehlgeschlagen. Bed-Kalibrierpunkt nicht gefunden."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "XYZ-Kalibrierung fehlgeschlagen. Bitte schauen Sie in das Handbuch."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "XYZ-Kalibrierung ok. X/Y-Achsen sind senkrecht zueinander. Glueckwunsch!"
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD "XYZ Kalibrierung in Ordnung. X/Y Achsen sind etwas schief."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME "XYZ Kalibrierung in Ordnung. Schiefheit wird automatisch korrigiert."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_LEFT_FAR "XYZ-Kalibrierung fehlgeschlagen. Linker vorderer Kalibrierpunkt ist zu weit vorne."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_RIGHT_FAR "XYZ-Kalibrierung fehlgeschlagen. Rechter vorderer Kalibrierpunkt ist zu weit vorne."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_FAILED_FRONT_BOTH_FAR "XYZ-Kalibrierung fehlgeschlagen. Vordere Kalibrierpunkte sind zu weit vorne."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_LEFT_FAR "XYZ-Kalibrierung ungenau. Linker vorderer Kalibrierpunkt ist zu weit vorne."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_RIGHT_FAR "XYZ-Kalibrierung ungenau. Rechter vorderer Kalibrierpunkt ist zu weit vorne."
+ #define(length = 20, lines = 8) MSG_BED_SKEW_OFFSET_DETECTION_WARNING_FRONT_BOTH_FAR "XYZ-Kalibrierung ungenau. Vordere Kalibrierpunkte sind zu weit vorne."
+
+#define(length = 20, lines = 4) MSG_BED_LEVELING_FAILED_POINT_LOW "Z-Kal. fehlgeschlg. Sensor nicht ausgeloest. Schmutzige Duese? Warte auf Reset"
+ #define(length = 20, lines = 4) MSG_BED_LEVELING_FAILED_POINT_HIGH "Z-Kalibrierung fehlgeschlg. Sensor zu hoch ausgeloest. Warte auf Reset."
+ #define(length = 20, lines = 4) MSG_BED_LEVELING_FAILED_PROBE_DISCONNECTED "Z-Kalibrierung fehlgeschlg. Sensor nicht angeschlossen. Warte auf Reset."
+
+#define(length = 20, lines = 2) MSG_NEW_FIRMWARE_AVAILABLE "Neue Firmware Version verfuegbar:"
+ #define(length = 20) MSG_NEW_FIRMWARE_PLEASE_UPGRADE "Bitte aktualisieren."
+
+ #define(length = 20, lines = 8) MSG_FOLLOW_CALIBRATION_FLOW "Der Drucker wurde noch nicht kalibriert. Bitte folgen Sie dem Handbuch, Kapitel First steps, Abschnitt Calibration flow."
+ #define(length = 20, lines = 12) MSG_BABYSTEP_Z_NOT_SET "Der Abstand zwischen der Spitze der Duese und der Bed ist noch nicht eingestellt. Bitte folgen Sie dem Handbuch, First steps, section First layer calibration."
+
+
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T0 "Filament in extruder 1 einlegen. Klicken wenn fertig."
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T1 "Filament in extruder 2 einlegen. Klicken wenn fertig."
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T2 "Filament in extruder 3 einlegen. Klicken wenn fertig."
+ #define(length = 20, lines = 4) MSG_FILAMENT_LOADING_T3 "Filament in extruder 4 einlegen. Klicken wenn fertig."
+ #define(length = 20, lines = 1) MSG_CHANGE_EXTR "Wechsel extruder"
+
+ #define(length = 20, lines = 4) MSG_FIL_ADJUSTING "Filament positionieren. Bitte warten."
+ #define(length = 20, lines = 8) MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamente sind jetzt eingestellt. Bitte reinigen Sie die Duese zur Kalibrierung. Klicken wenn fertig."
+
+ #define(length = 20, lines = 1) MSG_CALIBRATE_E "Kalibriere E"
+//#define(length=20, lines=1) "Reset E Cal."
+#define(length = 20, lines = 8) MSG_E_CAL_KNOB "Knopf drehen bis die Filamentmarkierung erreicht ist. Klicken wenn fertig."
+
+//#define(length=20, lines=1) MSG_FARM_CARD_MENU "Farm mode print"
+#define(length = 20, lines = 8) MSG_MARK_FIL "Filament 100mm vom Extrudergehaeuse markieren. Klicken wenn Fertig."
+ #define(length = 20, lines = 8) MSG_CLEAN_NOZZLE_E "E-Kalibrierung beendet. Bitte reinigen Sie die Duese. Klicken wenn fertig."
+ #define(length = 20, lines = 3) MSG_WAITING_TEMP "Warten auf Abkuehlung von Heater und Bed."
+ #define(length = 20, lines = 2) MSG_FILAMENT_CLEAN "Ist Farbe rein?"
+ #define(lenght = 20, lines = 1) MSG_UNLOADING_FILAMENT "Filament auswerfen"
+ #define(length = 20, lines = 8) MSG_PAPER "Legen ein Blatt Papier unter die Duese waehrend der Kalibrierung der ersten 4 Punkte. Wenn die Duese das Papier einklemmt, Drucker sofort ausschalten"
+
+#define MSG_BED_CORRECTION_MENU "Bed level Korrekt"
+ #define MSG_BED_CORRECTION_LEFT "Links [um]"
+ #define MSG_BED_CORRECTION_RIGHT "Rechts [um]"
+ #define MSG_BED_CORRECTION_FRONT "Vorne [um]"
+ #define MSG_BED_CORRECTION_REAR "Hinten [um]"
+ #define MSG_BED_CORRECTION_RESET "Ruecksetzen"
+
+#define MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
+ #define MSG_MENU_CALIBRATION "Kalibrierung"
+ #define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD Karte [normal]"
+ #define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD Karte [FlashAir]"
#define MSG_FINISHING_MOVEMENTS "Bewegung beenden"
#define MSG_PRINT_PAUSED "Druck pausiert"
#define MSG_RESUMING_PRINT "Druck weitergehen"
#define MSG_PID_EXTRUDER "PID Kalibrierung"
#define MSG_SET_TEMPERATURE "Temp. einsetzen"
#define MSG_PID_FINISHED "PID Kalib. fertig"
#define MSG_PID_RUNNING "PID Kalib."
#define MSG_CALIBRATE_PINDA "Kalibrieren"
#define MSG_CALIBRATION_PINDA_MENU "Temp. kalibrieren"
#define MSG_PINDA_NOT_CALIBRATED "Temperatur wurde nicht kalibriert"
#define MSG_PINDA_PREHEAT "PINDA erwaermen"
#define MSG_TEMP_CALIBRATION "Temp Kalib. "
#define MSG_TEMP_CALIBRATION_DONE "Temp. Kalibrierung fertig. Klicken um weiter zu gehen."
#define MSG_TEMP_CALIBRATION_ON "Temp. Kal. [ON]"
#define MSG_TEMP_CALIBRATION_OFF "Temp. Kal. [OFF]"
#define MSG_LOAD_ALL "Alle laden"
#define MSG_LOAD_FILAMENT_1 "Filament 1 laden"
#define MSG_LOAD_FILAMENT_2 "Filament 2 laden"
#define MSG_LOAD_FILAMENT_3 "Filament 3 laden"
#define MSG_LOAD_FILAMENT_4 "Filament 4 laden"
#define MSG_UNLOAD_FILAMENT_1 "Filam. 1 entladen"
#define MSG_UNLOAD_FILAMENT_2 "Filam. 2 entladen"
#define MSG_UNLOAD_FILAMENT_3 "Filam. 3 entladen"
#define MSG_UNLOAD_FILAMENT_4 "Filam. 4 entladen"
#define MSG_UNLOAD_ALL "Alles entladen"
#define MSG_PREPARE_FILAMENT "Filam. bereithalten"
#define MSG_ALL "Alle"
#define MSG_USED "Beim Druck benutzte"
#define MSG_CURRENT "Aktuelles"
#define MSG_CHOOSE_EXTRUDER "Waehlen Sie Extruder"
#define MSG_EXTRUDER "Extruder"
#define MSG_EXTRUDER_1 "Extruder 1"
#define MSG_EXTRUDER_2 "Extruder 2"
#define MSG_EXTRUDER_3 "Extruder 3"
#define MSG_EXTRUDER_4 "Extruder 4"

View file

@ -69,8 +69,19 @@
#define MSG_SETTINGS "Settings"
#define MSG_PREHEAT "Preheat"
#define MSG_UNLOAD_FILAMENT "Unload filament"
#define MSG_LOAD_FILAMENT "Load filament"
#define(length=17) MSG_UNLOAD_FILAMENT "Unload filament"
#define(length=17) MSG_LOAD_FILAMENT "Load filament"
#define(length=17) MSG_LOAD_FILAMENT_1 "Load filament 1"
#define(length=17) MSG_LOAD_FILAMENT_2 "Load filament 2"
#define(length=17) MSG_LOAD_FILAMENT_3 "Load filament 3"
#define(length=17) MSG_LOAD_FILAMENT_4 "Load filament 4"
#define(length=17) MSG_UNLOAD_FILAMENT_1 "Unload filament 1"
#define(length=17) MSG_UNLOAD_FILAMENT_2 "Unload filament 2"
#define(length=17) MSG_UNLOAD_FILAMENT_3 "Unload filament 3"
#define(length=17) MSG_UNLOAD_FILAMENT_4 "Unload filament 4"
#define MSG_UNLOAD_ALL "Unload all"
#define MSG_LOAD_ALL "Load all"
#define MSG_RECTRACT "Rectract"
#define MSG_ERROR "ERROR:"
@ -162,9 +173,9 @@
#define MSG_SELFTEST_ENDSTOPS "Endstops"
#define MSG_SELFTEST_MOTOR "Motor"
#define MSG_SELFTEST_ENDSTOP "Endstop"
#define MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
#define(length=20,lines=1) MSG_SELFTEST_ENDSTOP_NOTHIT "Endstop not hit"
#define MSG_SELFTEST_OK "Self test OK"
#define MSG_LOOSE_PULLEY "Loose pulley"
#define(length=20,lines=1) MSG_LOOSE_PULLEY "Loose pulley"
#define(length=20) MSG_SELFTEST_FAN "Fan test";
#define(length=20) MSG_SELFTEST_COOLING_FAN "Front print fan?";
@ -192,7 +203,7 @@
#define MSG_HOMEYZ_PROGRESS "Calibrating Z"
#define MSG_HOMEYZ_DONE "Calibration done"
#define MSG_SHOW_END_STOPS "Show end stops"
#define(length=17,lines=1) MSG_SHOW_END_STOPS "Show end stops"
#define MSG_CALIBRATE_BED "Calibrate XYZ"
#define MSG_CALIBRATE_BED_RESET "Reset XYZ calibr."
@ -208,6 +219,7 @@
#define(length=14) MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " of 9"
#define(length=60) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Measuring reference height of calibration point"
#define(length=14) MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " of 9"
#define(length=20) MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteration "
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "XYZ calibration failed. Bed calibration point was not found."
#define(length=20,lines=8) MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "XYZ calibration failed. Please consult the manual."
@ -237,8 +249,6 @@
#define(length=20, lines=4) MSG_FILAMENT_LOADING_T3 "Insert filament into extruder 4. Click when done."
#define(length=20, lines=1) MSG_CHANGE_EXTR "Change extruder"
#define(length=20, lines=1) MSG_FIL_LOADED_CHECK "Is filament loaded?"
#define(length=20, lines=2) MSG_FIL_TUNING "Rotate the knob to adjust filament."
#define(length=20, lines=4) MSG_FIL_ADJUSTING "Adjusting filaments. Please wait."
#define(length=20,lines=8) MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filaments are now adjusted. Please clean the nozzle for calibration. Click when done."
#define(length=20, lines=4) MSG_STACK_ERROR "Error - static memory has been overwritten"
@ -251,18 +261,45 @@
#define(length=20, lines=8) MSG_CLEAN_NOZZLE_E "E calibration finished. Please clean the nozzle. Click when done."
#define(length=20, lines=3) MSG_WAITING_TEMP "Waiting for nozzle and bed cooling"
#define(length=20, lines=2) MSG_FILAMENT_CLEAN "Is color clear?"
#define(lenght=20) MSG_UNLOADING_FILAMENT "Unloading filament"
#define(lenght=18, lines=1) MSG_UNLOADING_FILAMENT "Unloading filament"
#define(length=20, lines=8) MSG_PAPER "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."
#define MSG_BED_CORRECTION_MENU "Bed level correct"
#define MSG_BED_CORRECTION_LEFT "Left side um"
#define MSG_BED_CORRECTION_RIGHT "Right side um"
#define MSG_BED_CORRECTION_FRONT "Front side um"
#define MSG_BED_CORRECTION_REAR "Rear side um"
#define(length=14,lines=1) MSG_BED_CORRECTION_LEFT "Left side [um]"
#define(length=14,lines=1) MSG_BED_CORRECTION_RIGHT "Right side[um]"
#define(length=14,lines=1) MSG_BED_CORRECTION_FRONT "Front side[um]"
#define(length=14,lines=1) MSG_BED_CORRECTION_REAR "Rear side [um]"
#define MSG_BED_CORRECTION_RESET "Reset"
#define MSG_MESH_BED_LEVELING "Mesh Bed Leveling"
#define MSG_MENU_CALIBRATION "Calibration"
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
#define MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
#define MSG_PRINTER_DISCONNECTED "Printer disconnected"
#define(length=19, lines=1) MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF "SD card [normal]"
#define(length=19, lines=1) MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON "SD card [FlshAir]"
#define(length=20, lines=1) MSG_PRINTER_DISCONNECTED "Printer disconnected"
#define(length=20, lines=1) MSG_FINISHING_MOVEMENTS "Finishing movements"
#define(length=20, lines=1) MSG_PRINT_PAUSED "Print paused"
#define(length=20, lines=1) MSG_RESUMING_PRINT "Resuming print"
#define(length=17, lines=1) MSG_PID_EXTRUDER "PID calibration"
#define(length=19, lines=1) MSG_SET_TEMPERATURE "Set temperature:"
#define(length=20, lines=1) MSG_PID_FINISHED "PID cal. finished"
#define(length=20, lines=1) MSG_PID_RUNNING "PID cal. "
#define(length=17, lines=1) MSG_CALIBRATE_PINDA "Calibrate"
#define(length=17, lines=1) MSG_CALIBRATION_PINDA_MENU "Temp. calibration"
#define(length=20, lines=4) MSG_PINDA_NOT_CALIBRATED "Temperature calibration has not been run yet"
#define(length=20, lines=1) MSG_PINDA_PREHEAT "PINDA Heating"
#define(length=20, lines=1) MSG_TEMP_CALIBRATION "Temp. cal. "
#define(length=20, lines=4) MSG_TEMP_CALIBRATION_DONE "Temperature calibration is finished. Click to continue."
#define(length=20, lines=1) MSG_TEMP_CALIBRATION_ON "Temp. cal. [ON]"
#define(length=20, lines=1) MSG_TEMP_CALIBRATION_OFF "Temp. cal. [OFF]"
#define(length=20, lines=1) MSG_PREPARE_FILAMENT "Prepare new filament"
#define(length=19, lines=1) MSG_ALL "All"
#define(length=19, lines=1) MSG_USED "Used during print"
#define(length=19, lines=1) MSG_CURRENT "Current"
#define(length=20, lines=1) MSG_CHOOSE_EXTRUDER "Choose extruder:"
#define(length=17, lines=1) MSG_EXTRUDER "Extruder"
#define(length=17, lines=1) MSG_EXTRUDER_1 "Extruder 1"
#define(length=17, lines=1) MSG_EXTRUDER_2 "Extruder 2"
#define(length=17, lines=1) MSG_EXTRUDER_3 "Extruder 3"
#define(length=17, lines=1) MSG_EXTRUDER_4 "Extruder 4"

View file

@ -206,6 +206,7 @@
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Medir la altura del punto de la calibracion"
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " de 9"
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Reiteracion "
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Calibracion XYZ fallada. Puntos de calibracion en la cama no encontrados."
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Calibracion XYZ fallada. Consultar el manual por favor."
#define MSG_BED_SKEW_OFFSET_DETECTION_PERFECT "Calibracion XYZ ok. Ejes X/Y perpendiculares. Felicitaciones!"
@ -242,8 +243,7 @@
#define MSG_FILAMENT_LOADING_T2 "Insertar filamento en el extrusor 3. Haga clic una vez terminado."
#define MSG_FILAMENT_LOADING_T3 "Insertar filamento en el extrusor 4. Haga clic una vez terminado."
#define MSG_CHANGE_EXTR "Cambiar extrusor."
#define MSG_FIL_LOADED_CHECK "Esta cargado el filamento?"
#define MSG_FIL_TUNING "Rotar el mando para ajustar el filamento."
#define MSG_FIL_ADJUSTING "Ajustando filamentos. Esperar por favor."
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Filamentos ajustados. Limpie la boquilla para calibracion. Haga clic una vez terminado."
#define MSG_CALIBRATE_E "Calibrar E"
@ -254,3 +254,45 @@
#define MSG_FILAMENT_CLEAN "Es el nuevo color nitido?"
#define MSG_UNLOADING_FILAMENT "Soltando filamento"
#define MSG_PAPER "Colocar una hoja de papel sobre la superficie de impresion durante la calibracion de los primeros 4 puntos. Si la boquilla mueve el papel, apagar impresora inmediatamente."
#define MSG_FINISHING_MOVEMENTS "Term. movimientos"
#define MSG_PRINT_PAUSED "Impresion en pausa"
#define MSG_RESUMING_PRINT "Reanudar impresion"
#define MSG_PID_EXTRUDER "Calibracion PID"
#define MSG_SET_TEMPERATURE "Establecer temp.:"
#define MSG_PID_FINISHED "Cal. PID terminada"
#define MSG_PID_RUNNING "Cal. PID "
#define MSG_CALIBRATE_PINDA "Calibrar"
#define MSG_CALIBRATION_PINDA_MENU "Calibracion temp."
#define MSG_PINDA_NOT_CALIBRATED "La temperatura de calibracion no ha sido ajustada"
#define MSG_PINDA_PREHEAT "Calentando PINDA"
#define MSG_TEMP_CALIBRATION "Cal. temp. "
#define MSG_TEMP_CALIBRATION_DONE "Calibracon temperatura terminada. Presionar para continuar."
#define MSG_TEMP_CALIBRATION_ON "Cal. temp. [ON]"
#define MSG_TEMP_CALIBRATION_OFF "Cal. temp. [OFF]"
#define MSG_PREPARE_FILAMENT "Preparar filamento"
#define MSG_LOAD_ALL "Intr. todos fil."
#define MSG_LOAD_FILAMENT_1 "Introducir fil. 1"
#define MSG_LOAD_FILAMENT_2 "Introducir fil. 2"
#define MSG_LOAD_FILAMENT_3 "Introducir fil. 3"
#define MSG_LOAD_FILAMENT_4 "Introducir fil. 4"
#define MSG_UNLOAD_FILAMENT_1 "Soltar fil. 1"
#define MSG_UNLOAD_FILAMENT_2 "Soltar fil. 2"
#define MSG_UNLOAD_FILAMENT_3 "Soltar fil. 3"
#define MSG_UNLOAD_FILAMENT_4 "Soltar fil. 4"
#define MSG_UNLOAD_ALL "Soltar todos fil."
#define MSG_PREPARE_FILAMENT "Preparar filamento"
#define MSG_ALL "Todos"
#define MSG_USED "Usado en impresion"
#define MSG_CURRENT "Actual"
#define MSG_CHOOSE_EXTRUDER "Elegir extrusor:"
#define MSG_EXTRUDER "Extrusor"
#define MSG_EXTRUDER_1 "Extrusor 1"
#define MSG_EXTRUDER_2 "Extrusor 2"
#define MSG_EXTRUDER_3 "Extrusor 3"
#define MSG_EXTRUDER_4 "Extrusor 4"

View file

@ -196,6 +196,7 @@
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " su 9"
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Misurare l'altezza di riferimento del punto di calibrazione"
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " su 9"
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Reiterazione "
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Calibrazione XYZ fallita. Il punto di calibrazione sul letto non e' stato trovato."
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Calibrazione XYZ fallita. Si prega di consultare il manuale."
@ -220,10 +221,10 @@
#define MSG_BABYSTEP_Z_NOT_SET "Distanza tra la punta dell'ugello e la superficie del letto non ancora imposta. Si prega di seguire il manuale, capitolo First steps, sezione First layer calibration."
#define MSG_BED_CORRECTION_MENU "Correz. liv.letto"
#define MSG_BED_CORRECTION_LEFT "Lato sinistro"
#define MSG_BED_CORRECTION_RIGHT "Lato destro"
#define MSG_BED_CORRECTION_FRONT "Lato ateriore"
#define MSG_BED_CORRECTION_REAR "Lato posteriore"
#define MSG_BED_CORRECTION_LEFT "Sinistra [um]"
#define MSG_BED_CORRECTION_RIGHT "Destra [um]"
#define MSG_BED_CORRECTION_FRONT "Fronte [um]"
#define MSG_BED_CORRECTION_REAR "Retro [um]"
#define MSG_BED_CORRECTION_RESET "Reset"
#define MSG_MESH_BED_LEVELING "Mesh livel. letto"
@ -237,8 +238,7 @@
#define MSG_FILAMENT_LOADING_T2 "Inserire filamento nell'estrusore 3. Click per continuare."
#define MSG_FILAMENT_LOADING_T3 "Inserire filamento nell'estrusore 4. Click per continuare."
#define MSG_CHANGE_EXTR "Cambio estrusore."
#define MSG_FIL_LOADED_CHECK "Filamento caricato?"
#define MSG_FIL_TUNING "Girare la manopola per regolare il filamento"
#define MSG_FIL_ADJUSTING "Filamento in fase di regolazione. Attendere prego."
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "I filamenti sono regolati. Si prega di pulire l'ugello per la calibrazione. Click per continuare."
#define MSG_CALIBRATE_E "Calibra E"
@ -249,3 +249,41 @@
#define MSG_FILAMENT_CLEAN "Il colore e' nitido?"
#define MSG_UNLOADING_FILAMENT "Rilasc. filamento"
#define MSG_PAPER "Porre un foglio sotto l'ugello durante la calibrazione dei primi 4 punti. In caso l'ugello muova il foglio spegnere prontamente la stampante."
#define MSG_FINISHING_MOVEMENTS "Arresto in corso"
#define MSG_PRINT_PAUSED "Stampa in pausa"
#define MSG_RESUMING_PRINT "Stampa in ripresa"
#define MSG_PID_EXTRUDER "Calibrazione PID"
#define MSG_SET_TEMPERATURE "Imposta temperatura"
#define MSG_PID_FINISHED "Cal. PID completa"
#define MSG_PID_RUNNING "Cal. PID"
#define MSG_CALIBRATE_PINDA "Calibrare"
#define MSG_CALIBRATION_PINDA_MENU "Taratura temp."
#define MSG_PINDA_NOT_CALIBRATED "Taratura della temperatura non ancora eseguita"
#define MSG_PINDA_PREHEAT "Riscald. PINDA"
#define MSG_TEMP_CALIBRATION "Cal. temp. "
#define MSG_TEMP_CALIBRATION_DONE "Taratura temperatura terminata. Fare click per continuare."
#define MSG_TEMP_CALIBRATION_ON "Cal. temp. [ON]"
#define MSG_TEMP_CALIBRATION_OFF "Cal. temp. [OFF]"
#define MSG_LOAD_ALL "Caricare tutti"
#define MSG_LOAD_FILAMENT_1 "Caricare fil. 1"
#define MSG_LOAD_FILAMENT_2 "Caricare fil. 2"
#define MSG_LOAD_FILAMENT_3 "Caricare fil. 3"
#define MSG_LOAD_FILAMENT_4 "Caricare fil. 4"
#define MSG_UNLOAD_FILAMENT_1 "Rilasciare fil. 1"
#define MSG_UNLOAD_FILAMENT_2 "Rilasciare fil. 1"
#define MSG_UNLOAD_FILAMENT_3 "Rilasciare fil. 1"
#define MSG_UNLOAD_FILAMENT_4 "Rilasciare fil. 1"
#define MSG_UNLOAD_ALL "Rilasciare tutti"
#define MSG_PREPARE_FILAMENT "Preparare filamento"
#define MSG_ALL "Tutti"
#define MSG_USED "Usati nella stampa"
#define MSG_CURRENT "Attuale"
#define MSG_CHOOSE_EXTRUDER "Seleziona estrusore:"
#define MSG_EXTRUDER "Estrusore"
#define MSG_EXTRUDER_1 "Estrusore 1"
#define MSG_EXTRUDER_2 "Estrusore 2"
#define MSG_EXTRUDER_3 "Estrusore 3"
#define MSG_EXTRUDER_4 "Estrusore 4"

View file

@ -211,6 +211,7 @@
#define MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 " z 9"
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 "Okreslam wysokosc odniesienia punktu kalibracyjnego"
#define MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2 " z 9"
#define MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION "Iteracja "
#define MSG_BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND "Kalibr. XYZ nieudana. Kalibracyjny punkt podkladki nieznaleziony."
#define MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED "Kalibracja XYZ niepowiedziona. Sprawdzic w instrukcji."
@ -248,8 +249,7 @@
#define MSG_FILAMENT_LOADING_T2 "Wloz filament do ekstrudera 3. Potwierdz przyciskiem."
#define MSG_FILAMENT_LOADING_T3 "Wloz filament do ekstrudera 4. Potwierdz przyciskiem."
#define MSG_CHANGE_EXTR "Zmienic ekstruder"
#define MSG_FIL_LOADED_CHECK "Czy filament jest wprowadzony?"
#define MSG_FIL_TUNING "Obrotem przycisku dostroj pozycje filamentu."
#define MSG_FIL_ADJUSTING "Przebiega wyrownanie filamentow. Prosze czekac."
#define MSG_CONFIRM_NOZZLE_CLEAN_FIL_ADJ "Dla prawidlowej kalibracji prosze oczyscic dysze. Potem potwierdzic przyciskiem."
#define MSG_CALIBRATE_E "Kalibruj E"
@ -260,3 +260,42 @@
#define MSG_FILAMENT_CLEAN "Czy kolor jest czysty?"
#define MSG_UNLOADING_FILAMENT "Wysuwam filament"
#define MSG_PAPER "Umiesc kartke papieru na podkladce i trzymaj pod dysza podczas pomiaru pierwszych 4 punktow. Jesli dysza zahaczy o papier, wylacz drukarke."
#define MSG_FINISHING_MOVEMENTS "Konczenie druku"
#define MSG_PRINT_PAUSED "Druk zatrzymany"
#define MSG_RESUMING_PRINT "Wznawianie druku"
#define MSG_PID_EXTRUDER "Kalibracja PID"
#define MSG_SET_TEMPERATURE "Ustawic temperature"
#define MSG_PID_FINISHED "Kal. PID zakonczona"
#define MSG_PID_RUNNING "Kal. PID"
#define MSG_CALIBRATE_PINDA "Skalibrowac"
#define MSG_CALIBRATION_PINDA_MENU "Cieplna kalibr."
#define MSG_PINDA_NOT_CALIBRATED "Cieplna kalibracja nie byla przeprowadzona"
#define MSG_PINDA_PREHEAT "Grzanie PINDA"
#define MSG_TEMP_CALIBRATION "Ciepl. kal. "
#define MSG_TEMP_CALIBRATION_DONE "Cieplna kalibracja zakonczona. Kontynuuj przyciskiem"
#define MSG_TEMP_CALIBRATION_ON "Ciepl. kal. [ON]"
#define MSG_TEMP_CALIBRATION_OFF "Ciepl. kal. [OFF]"
#define MSG_PREPARE_FILAMENT "Przygotuj filament"
#define MSG_LOAD_ALL "Zalad. wszystkie"
#define MSG_LOAD_FILAMENT_1 "Zaladowac fil. 1"
#define MSG_LOAD_FILAMENT_2 "Zaladowac fil. 2"
#define MSG_LOAD_FILAMENT_3 "Zaladowac fil. 3"
#define MSG_LOAD_FILAMENT_4 "Zaladowac fil. 4"
#define MSG_UNLOAD_FILAMENT_1 "Wyjac filament 1"
#define MSG_UNLOAD_FILAMENT_2 "Wyjac filament 2"
#define MSG_UNLOAD_FILAMENT_3 "Wyjac filament 3"
#define MSG_UNLOAD_FILAMENT_4 "Wyjac filament 4"
#define MSG_UNLOAD_ALL "Wyjac wszystkie"
#define MSG_PREPARE_FILAMENT "Przygotuj filament"
#define MSG_ALL "Wszystko"
#define MSG_USED "Uzyte przy druku"
#define MSG_CURRENT "Tylko aktualne"
#define MSG_CHOOSE_EXTRUDER "Wybierz ekstruder"
#define MSG_EXTRUDER "Ekstruder"
#define MSG_EXTRUDER_1 "Ekstruder 1"
#define MSG_EXTRUDER_2 "Ekstruder 2"
#define MSG_EXTRUDER_3 "Ekstruder 3"
#define MSG_EXTRUDER_4 "Ekstruder 4"

29
Firmware/le.sh Normal file
View file

@ -0,0 +1,29 @@
# line ending management script
# CRLF - windows default ('\r\n')
# LF - unix default ('\n')
# arguments:
# ?crlf - print all .cpp and .h files with CRLF line endings
# ?lf - print all .cpp and .h files with LF line endings
# crlf - replace line endings in all .cpp and .h files to CRLF
# lf - replace line endings in all .cpp and .h files to LF
if [ "$1" == "?crlf" ] || [ $# -eq 0 ]; then
echo 'cpp and h files with CRLF line endings:'
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep CRLF | sed 's/:.*//g'
elif [ "$1" == "?lf" ]; then
echo 'cpp and h files with LF line endings:'
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep -v CRLF | sed 's/:.*//g'
fi
if [ "$1" == "crlf" ]; then
echo 'replacing LF with CRLF in all cpp and h files:'
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep -v CRLF | sed 's/:.*//g' | while read fn; do
echo "$fn"
sed -i 's/$/\r/g' $fn
done
elif [ "$1" == "lf" ]; then
echo 'replacing CRLF with LF in all cpp and h files:'
find {*.cpp,*.h} -not -type d -exec file "{}" ";" | grep CRLF | sed 's/:.*//g' | while read fn; do
echo "$fn"
sed -i 's/\r\n/\n/g' $fn
done
fi

View file

@ -29,11 +29,6 @@ float world2machine_shift[2];
#define MACHINE_AXIS_SCALE_X 1.f
#define MACHINE_AXIS_SCALE_Y 1.f
// 0.12 degrees equals to an offset of 0.5mm on 250mm length.
#define BED_SKEW_ANGLE_MILD (0.12f * M_PI / 180.f)
// 0.25 degrees equals to an offset of 1.1mm on 250mm length.
#define BED_SKEW_ANGLE_EXTREME (0.25f * M_PI / 180.f)
#define BED_CALIBRATION_POINT_OFFSET_MAX_EUCLIDIAN (0.8f)
#define BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_X (0.8f)
#define BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_Y (1.5f)
@ -48,6 +43,11 @@ float world2machine_shift[2];
// by the Least Squares fitting and the X coordinate will be weighted low.
#define Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH (Y_MIN_POS - 0.5f)
// 0.12 degrees equals to an offset of 0.5mm on 250mm length.
const float bed_skew_angle_mild = (0.12f * M_PI / 180.f);
// 0.25 degrees equals to an offset of 1.1mm on 250mm length.
const float bed_skew_angle_extreme = (0.25f * M_PI / 180.f);
// Positions of the bed reference points in the machine coordinates, referenced to the P.I.N.D.A sensor.
// The points are ordered in a zig-zag fashion to speed up the calibration.
const float bed_ref_points[] PROGMEM = {
@ -75,14 +75,20 @@ const float bed_ref_points_4[] PROGMEM = {
static inline float sqr(float x) { return x * x; }
static inline bool point_on_1st_row(const uint8_t i, const uint8_t npts)
{
if (npts == 4) return (i == 0);
else return (i < 3);
}
// Weight of a point coordinate in a least squares optimization.
// The first row of points may not be fully reachable
// and the y values may be shortened a bit by the bed carriage
// pulling the belt up.
static inline float point_weight_x(const uint8_t i, const float &y)
static inline float point_weight_x(const uint8_t i, const uint8_t npts, const float &y)
{
float w = 1.f;
if (i < 3) {
if (point_on_1st_row(i, npts)) {
if (y >= Y_MIN_POS_CALIBRATION_POINT_ACCURATE) {
w = WEIGHT_FIRST_ROW_X_HIGH;
} else if (y < Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH) {
@ -101,10 +107,10 @@ static inline float point_weight_x(const uint8_t i, const float &y)
// The first row of points may not be fully reachable
// and the y values may be shortened a bit by the bed carriage
// pulling the belt up.
static inline float point_weight_y(const uint8_t i, const float &y)
static inline float point_weight_y(const uint8_t i, const uint8_t npts, const float &y)
{
float w = 1.f;
if (i < 3) {
if (point_on_1st_row(i, npts)) {
if (y >= Y_MIN_POS_CALIBRATION_POINT_ACCURATE) {
w = WEIGHT_FIRST_ROW_Y_HIGH;
} else if (y < Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH) {
@ -138,6 +144,8 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
)
{
if (verbosity_level >= 10) {
SERIAL_ECHOLNPGM("calculate machine skew and offset LS");
// Show the initial state, before the fitting.
SERIAL_ECHOPGM("X vector, initial: ");
MYSERIAL.print(vec_x[0], 5);
@ -210,7 +218,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
(c == 0) ? 1.f :
((c == 2) ? (-s1 * measured_pts[2 * i]) :
(-c2 * measured_pts[2 * i + 1]));
float w = point_weight_x(i, measured_pts[2 * i + 1]);
float w = point_weight_x(i, npts, measured_pts[2 * i + 1]);
acc += a * b * w;
}
// Second for the residuum in the y axis.
@ -225,7 +233,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
(c == 1) ? 1.f :
((c == 2) ? ( c1 * measured_pts[2 * i]) :
(-s2 * measured_pts[2 * i + 1]));
float w = point_weight_y(i, measured_pts[2 * i + 1]);
float w = point_weight_y(i, npts, measured_pts[2 * i + 1]);
acc += a * b * w;
}
}
@ -241,7 +249,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
((r == 2) ? (-s1 * measured_pts[2 * i]) :
(-c2 * measured_pts[2 * i + 1])));
float fx = c1 * measured_pts[2 * i] - s2 * measured_pts[2 * i + 1] + cntr[0] - pgm_read_float(true_pts + i * 2);
float w = point_weight_x(i, measured_pts[2 * i + 1]);
float w = point_weight_x(i, npts, measured_pts[2 * i + 1]);
acc += j * fx * w;
}
{
@ -251,7 +259,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
((r == 2) ? ( c1 * measured_pts[2 * i]) :
(-s2 * measured_pts[2 * i + 1])));
float fy = s1 * measured_pts[2 * i] + c2 * measured_pts[2 * i + 1] + cntr[1] - pgm_read_float(true_pts + i * 2 + 1);
float w = point_weight_y(i, measured_pts[2 * i + 1]);
float w = point_weight_y(i, npts, measured_pts[2 * i + 1]);
acc += j * fy * w;
}
}
@ -278,8 +286,8 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
if (verbosity_level >= 20) {
SERIAL_ECHOPGM("iteration: ");
MYSERIAL.print(iter, 0);
SERIAL_ECHOPGM("correction vector: ");
MYSERIAL.print(int(iter));
SERIAL_ECHOPGM("; correction vector: ");
MYSERIAL.print(h[0], 5);
SERIAL_ECHOPGM(", ");
MYSERIAL.print(h[1], 5);
@ -308,13 +316,13 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
BedSkewOffsetDetectionResultType result = BED_SKEW_OFFSET_DETECTION_PERFECT;
{
float angleDiff = fabs(a2 - a1);
if (angleDiff > BED_SKEW_ANGLE_MILD)
result = (angleDiff > BED_SKEW_ANGLE_EXTREME) ?
angleDiff = fabs(a2 - a1);
if (angleDiff > bed_skew_angle_mild)
result = (angleDiff > bed_skew_angle_extreme) ?
BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME :
BED_SKEW_OFFSET_DETECTION_SKEW_MILD;
if (fabs(a1) > BED_SKEW_ANGLE_EXTREME ||
fabs(a2) > BED_SKEW_ANGLE_EXTREME)
if (fabs(a1) > bed_skew_angle_extreme ||
fabs(a2) > bed_skew_angle_extreme)
result = BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME;
}
@ -357,18 +365,35 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
float errX = sqr(pgm_read_float(true_pts + i * 2) - x);
float errY = sqr(pgm_read_float(true_pts + i * 2 + 1) - y);
float err = sqrt(errX + errY);
if (i < 3) {
float w = point_weight_y(i, measured_pts[2 * i + 1]);
if (sqrt(errX) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_X ||
(w != 0.f && sqrt(errY) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_Y))
result = BED_SKEW_OFFSET_DETECTION_FITTING_FAILED;
} else {
if (err > BED_CALIBRATION_POINT_OFFSET_MAX_EUCLIDIAN)
result = BED_SKEW_OFFSET_DETECTION_FITTING_FAILED;
}
if (verbosity_level >= 10) {
SERIAL_ECHOPGM("point #");
MYSERIAL.print(int(i));
SERIAL_ECHOLNPGM(":");
}
if (point_on_1st_row(i, npts)) {
if(verbosity_level >= 20) SERIAL_ECHOPGM("Point on first row");
float w = point_weight_y(i, npts, measured_pts[2 * i + 1]);
if (sqrt(errX) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_X ||
(w != 0.f && sqrt(errY) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_Y)) {
result = BED_SKEW_OFFSET_DETECTION_FITTING_FAILED;
if (verbosity_level >= 20) {
SERIAL_ECHOPGM(", weigth Y: ");
MYSERIAL.print(w);
if (sqrt(errX) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_X) SERIAL_ECHOPGM(", error X > max. error X");
if (w != 0.f && sqrt(errY) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_Y) SERIAL_ECHOPGM(", error Y > max. error Y");
}
}
}
else {
if(verbosity_level >=20 ) SERIAL_ECHOPGM("Point not on first row");
if (err > BED_CALIBRATION_POINT_OFFSET_MAX_EUCLIDIAN) {
result = BED_SKEW_OFFSET_DETECTION_FITTING_FAILED;
if(verbosity_level >= 20) SERIAL_ECHOPGM(", error > max. error euclidian");
}
}
if (verbosity_level >= 10) {
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("measured: (");
MYSERIAL.print(measured_pts[i * 2], 5);
SERIAL_ECHOPGM(", ");
@ -381,14 +406,30 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
MYSERIAL.print(pgm_read_float(true_pts + i * 2), 5);
SERIAL_ECHOPGM(", ");
MYSERIAL.print(pgm_read_float(true_pts + i * 2 + 1), 5);
SERIAL_ECHOPGM("), error: ");
SERIAL_ECHOLNPGM(")");
SERIAL_ECHOPGM("error: ");
MYSERIAL.print(err);
SERIAL_ECHOPGM(", error X: ");
MYSERIAL.print(sqrt(errX));
SERIAL_ECHOPGM(", error Y: ");
MYSERIAL.print(sqrt(errY));
SERIAL_ECHOLNPGM("");
SERIAL_ECHOLNPGM("");
}
}
if (verbosity_level >= 20) {
SERIAL_ECHOLNPGM("Max. errors:");
SERIAL_ECHOPGM("Max. error X:");
MYSERIAL.println(BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_X);
SERIAL_ECHOPGM("Max. error Y:");
MYSERIAL.println(BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_Y);
SERIAL_ECHOPGM("Max. error euclidian:");
MYSERIAL.println(BED_CALIBRATION_POINT_OFFSET_MAX_EUCLIDIAN);
SERIAL_ECHOLNPGM("");
}
#if 0
if (result == BED_SKEW_OFFSET_DETECTION_PERFECT && fabs(a1) < BED_SKEW_ANGLE_MILD && fabs(a2) < BED_SKEW_ANGLE_MILD) {
if (result == BED_SKEW_OFFSET_DETECTION_PERFECT && fabs(a1) < bed_skew_angle_mild && fabs(a2) < bed_skew_angle_mild) {
if (verbosity_level > 0)
SERIAL_ECHOLNPGM("Very little skew detected. Disabling skew correction.");
// Just disable the skew correction.
@ -415,7 +456,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
for (int8_t i = 0; i < npts; ++ i) {
float x = vec_x[0] * measured_pts[i * 2] + vec_y[0] * measured_pts[i * 2 + 1];
float y = vec_x[1] * measured_pts[i * 2] + vec_y[1] * measured_pts[i * 2 + 1];
float w = point_weight_x(i, y);
float w = point_weight_x(i, npts, y);
cntr[0] += w * (pgm_read_float(true_pts + i * 2) - x);
wx += w;
if (verbosity_level >= 20) {
@ -430,7 +471,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
SERIAL_ECHOLNPGM("wx:");
MYSERIAL.print(wx);
}
w = point_weight_y(i, y);
w = point_weight_y(i, npts, y);
cntr[1] += w * (pgm_read_float(true_pts + i * 2 + 1) - y);
wy += w;
@ -528,6 +569,13 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
MYSERIAL.print(sqrt(sqr(measured_pts[i * 2] - x) + sqr(measured_pts[i * 2 + 1] - y)));
SERIAL_ECHOLNPGM("");
}
if (verbosity_level >= 20) {
SERIAL_ECHOLNPGM("");
SERIAL_ECHOLNPGM("Calculate offset and skew returning result:");
MYSERIAL.print(int(result));
SERIAL_ECHOLNPGM("");
SERIAL_ECHOLNPGM("");
}
delay_keep_alive(100);
}
@ -619,7 +667,7 @@ static inline bool vec_undef(const float v[2])
void world2machine_initialize()
{
// SERIAL_ECHOLNPGM("world2machine_initialize()");
//SERIAL_ECHOLNPGM("world2machine_initialize");
float cntr[2] = {
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_CENTER+0)),
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_CENTER+4))
@ -635,7 +683,7 @@ void world2machine_initialize()
bool reset = false;
if (vec_undef(cntr) || vec_undef(vec_x) || vec_undef(vec_y)) {
// SERIAL_ECHOLNPGM("Undefined bed correction matrix.");
SERIAL_ECHOLNPGM("Undefined bed correction matrix.");
reset = true;
}
else {
@ -740,9 +788,9 @@ static inline void update_current_position_z()
}
// At the current position, find the Z stop.
inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter)
inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, int verbosity_level)
{
// SERIAL_ECHOLNPGM("find_bed_induction_sensor_point_z 1");
if(verbosity_level >= 10) SERIAL_ECHOLNPGM("find bed induction sensor point z");
bool endstops_enabled = enable_endstops(true);
bool endstop_z_enabled = enable_z_endstop(false);
float z = 0.f;
@ -795,8 +843,9 @@ error:
#define FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS (6.f)
#define FIND_BED_INDUCTION_SENSOR_POINT_XY_STEP (1.f)
#define FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP (0.2f)
inline bool find_bed_induction_sensor_point_xy()
inline bool find_bed_induction_sensor_point_xy(int verbosity_level)
{
if(verbosity_level >= 10) MYSERIAL.println("find bed induction sensor point xy");
float feedrate = homing_feedrate[X_AXIS] / 60.f;
bool found = false;
@ -807,14 +856,22 @@ inline bool find_bed_induction_sensor_point_xy()
float y1 = current_position[Y_AXIS] + FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS;
uint8_t nsteps_y;
uint8_t i;
if (x0 < X_MIN_POS)
if (x0 < X_MIN_POS) {
x0 = X_MIN_POS;
if (x1 > X_MAX_POS)
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("X searching radius lower than X_MIN. Clamping was done.");
}
if (x1 > X_MAX_POS) {
x1 = X_MAX_POS;
if (y0 < Y_MIN_POS_FOR_BED_CALIBRATION)
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("X searching radius higher than X_MAX. Clamping was done.");
}
if (y0 < Y_MIN_POS_FOR_BED_CALIBRATION) {
y0 = Y_MIN_POS_FOR_BED_CALIBRATION;
if (y1 > Y_MAX_POS)
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("Y searching radius lower than Y_MIN. Clamping was done.");
}
if (y1 > Y_MAX_POS) {
y1 = Y_MAX_POS;
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("Y searching radius higher than X_MAX. Clamping was done.");
}
nsteps_y = int(ceil((y1 - y0) / FIND_BED_INDUCTION_SENSOR_POINT_XY_STEP));
enable_endstops(false);
@ -1240,6 +1297,7 @@ inline bool improve_bed_induction_sensor_point3(int verbosity_level)
float a, b;
bool result = true;
if (verbosity_level >= 20) MYSERIAL.println("Improve bed induction sensor point3");
// Was the sensor point detected too far in the minus Y axis?
// If yes, the center of the induction point cannot be reached by the machine.
{
@ -1574,7 +1632,7 @@ inline void scan_bed_induction_sensor_point()
#define MESH_BED_CALIBRATION_SHOW_LCD
BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level)
BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level, uint8_t &too_far_mask)
{
// Don't let the manage_inactivity() function remove power from the motors.
refresh_cmd_timeout();
@ -1586,11 +1644,39 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
float *vec_y = vec_x + 2;
float *cntr = vec_y + 2;
memset(pts, 0, sizeof(float) * 7 * 7);
uint8_t iteration = 0;
BedSkewOffsetDetectionResultType result;
// SERIAL_ECHOLNPGM("find_bed_offset_and_skew verbosity level: ");
// SERIAL_ECHO(int(verbosity_level));
// SERIAL_ECHOPGM("");
while (iteration < 3) {
SERIAL_ECHOPGM("Iteration: ");
MYSERIAL.println(int(iteration + 1));
if (verbosity_level >= 20) {
SERIAL_ECHOLNPGM("Vectors: ");
SERIAL_ECHOPGM("vec_x[0]:");
MYSERIAL.print(vec_x[0], 5);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("vec_x[1]:");
MYSERIAL.print(vec_x[1], 5);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("vec_y[0]:");
MYSERIAL.print(vec_y[0], 5);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("vec_y[1]:");
MYSERIAL.print(vec_y[1], 5);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("cntr[0]:");
MYSERIAL.print(cntr[0], 5);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("cntr[1]:");
MYSERIAL.print(cntr[1], 5);
SERIAL_ECHOLNPGM("");
}
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
uint8_t next_line;
lcd_display_message_fullscreen_P(MSG_FIND_BED_OFFSET_AND_SKEW_LINE1, next_line);
@ -1599,16 +1685,22 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
// Collect the rear 2x3 points.
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH + FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP * iteration * 0.3;
for (int k = 0; k < 4; ++k) {
// Don't let the manage_inactivity() function remove power from the motors.
refresh_cmd_timeout();
#ifdef MESH_BED_CALIBRATION_SHOW_LCD
lcd_implementation_print_at(0, next_line, k + 1);
lcd_printPGM(MSG_FIND_BED_OFFSET_AND_SKEW_LINE2);
if (iteration > 0) {
lcd_print_at_PGM(0, next_line + 1, MSG_FIND_BED_OFFSET_AND_SKEW_ITERATION);
lcd_implementation_print(int(iteration + 1));
}
#endif /* MESH_BED_CALIBRATION_SHOW_LCD */
float *pt = pts + k * 2;
// Go up to z_initial.
go_to_current(homing_feedrate[Z_AXIS] / 60.f);
if (verbosity_level >= 20) {
// Go to Y0, wait, then go to Y-4.
@ -1622,14 +1714,42 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
delay_keep_alive(5000);
}
// Go to the measurement point position.
//if (iteration == 0) {
current_position[X_AXIS] = pgm_read_float(bed_ref_points_4 + k * 2);
current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + k * 2 + 1);
/*}
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().
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];
// The calibration points are very close to the min Y.
if (current_position[Y_AXIS] < Y_MIN_POS_FOR_BED_CALIBRATION)
current_position[Y_AXIS] = Y_MIN_POS_FOR_BED_CALIBRATION;
}*/
if (verbosity_level >= 20) {
SERIAL_ECHOPGM("current_position[X_AXIS]:");
MYSERIAL.print(current_position[X_AXIS], 5);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("current_position[Y_AXIS]:");
MYSERIAL.print(current_position[Y_AXIS], 5);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("current_position[Z_AXIS]:");
MYSERIAL.print(current_position[Z_AXIS], 5);
SERIAL_ECHOLNPGM("");
}
go_to_current(homing_feedrate[X_AXIS] / 60.f);
if (verbosity_level >= 10)
delay_keep_alive(3000);
if (! find_bed_induction_sensor_point_xy())
if (!find_bed_induction_sensor_point_xy(verbosity_level))
return BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND;
#if 1
if (k == 0) {
// Improve the position of the 1st row sensor points by a zig-zag movement.
find_bed_induction_sensor_point_z();
@ -1654,14 +1774,37 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
delay_keep_alive(3000);
// Save the detected point position and then clamp the Y coordinate, which may have been estimated
// to lie outside the machine working space.
pt[0] = current_position[X_AXIS];
pt[1] = current_position[Y_AXIS];
if (verbosity_level >= 20) {
SERIAL_ECHOLNPGM("Measured:");
MYSERIAL.println(current_position[X_AXIS]);
MYSERIAL.println(current_position[Y_AXIS]);
}
pt[0] = (pt[0] * iteration) / (iteration + 1);
pt[0] += (current_position[X_AXIS]/(iteration + 1)); //count average
pt[1] = (pt[1] * iteration) / (iteration + 1);
pt[1] += (current_position[Y_AXIS] / (iteration + 1));
//pt[0] += current_position[X_AXIS];
//if(iteration > 0) pt[0] = pt[0] / 2;
//pt[1] += current_position[Y_AXIS];
//if (iteration > 0) pt[1] = pt[1] / 2;
if (verbosity_level >= 20) {
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("pt[0]:");
MYSERIAL.println(pt[0]);
SERIAL_ECHOPGM("pt[1]:");
MYSERIAL.println(pt[1]);
}
if (current_position[Y_AXIS] < Y_MIN_POS)
current_position[Y_AXIS] = Y_MIN_POS;
// Start searching for the other points at 3mm above the last point.
current_position[Z_AXIS] += 3.f;
cntr[0] += pt[0];
cntr[1] += pt[1];
current_position[Z_AXIS] += 3.f + FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP * iteration * 0.3;
//cntr[0] += pt[0];
//cntr[1] += pt[1];
if (verbosity_level >= 10 && k == 0) {
// Show the zero. Test, whether the Y motor skipped steps.
current_position[Y_AXIS] = MANUAL_Y_HOME_POS;
@ -1685,7 +1828,16 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
}
}
BedSkewOffsetDetectionResultType result = calculate_machine_skew_and_offset_LS(pts, 4, bed_ref_points_4, vec_x, vec_y, cntr, verbosity_level);
if (pts[1] < Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH) {
too_far_mask |= 1 << 1; //front center point is out of reach
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("WARNING: Front point not reachable. Y coordinate:");
MYSERIAL.print(pts[1]);
SERIAL_ECHOPGM(" < ");
MYSERIAL.println(Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH);
}
result = calculate_machine_skew_and_offset_LS(pts, 4, bed_ref_points_4, vec_x, vec_y, cntr, verbosity_level);
if (result >= 0) {
world2machine_update(vec_x, vec_y, cntr);
#if 1
@ -1721,6 +1873,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
// Correct the current_position to match the transformed coordinate system after world2machine_rotation_and_skew and world2machine_shift were set.
world2machine_update_current();
if (verbosity_level >= 20) {
// Test the positions. Are the positions reproducible? Now the calibration is active in the planner.
delay_keep_alive(3000);
@ -1735,8 +1888,11 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
delay_keep_alive(3000);
}
}
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++;
}
return result;
}
@ -1756,6 +1912,8 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
float *cntr = vec_y + 2;
memset(pts, 0, sizeof(float) * 7 * 7);
if (verbosity_level >= 10) SERIAL_ECHOLNPGM("Improving bed offset and skew");
// Cache the current correction matrix.
world2machine_initialize();
vec_x[0] = world2machine_rotation_and_skew[0][0];
@ -1801,7 +1959,7 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
delay_keep_alive(5000);
current_position[Y_AXIS] = Y_MIN_POS;
go_to_current(homing_feedrate[X_AXIS] / 60.f);
SERIAL_ECHOLNPGM("At Y-4");
SERIAL_ECHOLNPGM("At Y_MIN_POS");
delay_keep_alive(5000);
}
// Go to the measurement point.
@ -1809,8 +1967,15 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
current_position[X_AXIS] = vec_x[0] * pgm_read_float(bed_ref_points+mesh_point*2) + vec_y[0] * pgm_read_float(bed_ref_points+mesh_point*2+1) + cntr[0];
current_position[Y_AXIS] = vec_x[1] * pgm_read_float(bed_ref_points+mesh_point*2) + vec_y[1] * pgm_read_float(bed_ref_points+mesh_point*2+1) + cntr[1];
// The calibration points are very close to the min Y.
if (current_position[Y_AXIS] < Y_MIN_POS_FOR_BED_CALIBRATION)
if (current_position[Y_AXIS] < Y_MIN_POS_FOR_BED_CALIBRATION){
current_position[Y_AXIS] = Y_MIN_POS_FOR_BED_CALIBRATION;
if (verbosity_level >= 20) {
SERIAL_ECHOPGM("Calibration point ");
SERIAL_ECHO(mesh_point);
SERIAL_ECHOPGM("lower than Ymin. Y coordinate clamping was used.");
SERIAL_ECHOLNPGM("");
}
}
go_to_current(homing_feedrate[X_AXIS]/60);
// Find its Z position by running the normal vertical search.
if (verbosity_level >= 10)
@ -1891,6 +2056,7 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
if (verbosity_level >= 5) {
// Test the positions. Are the positions reproducible?
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
for (int8_t mesh_point = 0; mesh_point < 9; ++ mesh_point) {
// Don't let the manage_inactivity() function remove power from the motors.
refresh_cmd_timeout();
@ -1925,6 +2091,16 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
// In case of success, update the too_far_mask from the calculated points.
for (uint8_t mesh_point = 0; mesh_point < 3; ++ mesh_point) {
float y = vec_x[1] * pgm_read_float(bed_ref_points+mesh_point*2) + vec_y[1] * pgm_read_float(bed_ref_points+mesh_point*2+1) + cntr[1];
distance_from_min[mesh_point] = (y - Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH);
if (verbosity_level >= 20) {
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("Distance from min:");
MYSERIAL.print(distance_from_min[mesh_point]);
SERIAL_ECHOLNPGM("");
SERIAL_ECHOPGM("y:");
MYSERIAL.print(y);
SERIAL_ECHOLNPGM("");
}
if (y < Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH)
too_far_mask |= 1 << mesh_point;
}
@ -1950,6 +2126,7 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
if (verbosity_level >= 5) {
// Test the positions. Are the positions reproducible? Now the calibration is active in the planner.
delay_keep_alive(3000);
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
for (int8_t mesh_point = 0; mesh_point < 9; ++ mesh_point) {
// Don't let the manage_inactivity() function remove power from the motors.
refresh_cmd_timeout();
@ -2217,7 +2394,7 @@ static int babystepLoadZ = 0;
void babystep_apply()
{
// Apply Z height correction aka baby stepping before mesh bed leveling gets activated.
if(calibration_status() == CALIBRATION_STATUS_CALIBRATED)
if(calibration_status() < CALIBRATION_STATUS_LIVE_ADJUST)
{
check_babystep(); //checking if babystep is in allowed range, otherwise setting babystep to 0
@ -2255,3 +2432,33 @@ void babystep_reset()
{
babystepLoadZ = 0;
}
void count_xyz_details() {
float a1, a2;
float cntr[2] = {
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_CENTER + 0)),
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_CENTER + 4))
};
float vec_x[2] = {
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_VEC_X + 0)),
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_VEC_X + 4))
};
float vec_y[2] = {
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_VEC_Y + 0)),
eeprom_read_float((float*)(EEPROM_BED_CALIBRATION_VEC_Y + 4))
};
a2 = -1 * asin(vec_y[0] / MACHINE_AXIS_SCALE_Y);
a1 = asin(vec_x[1] / MACHINE_AXIS_SCALE_X);
angleDiff = fabs(a2 - a1);
for (uint8_t mesh_point = 0; mesh_point < 3; ++mesh_point) {
float y = vec_x[1] * pgm_read_float(bed_ref_points + mesh_point * 2) + vec_y[1] * pgm_read_float(bed_ref_points + mesh_point * 2 + 1) + cntr[1];
distance_from_min[mesh_point] = (y - Y_MIN_POS_CALIBRATION_POINT_OUT_OF_REACH);
}
}
/*countDistanceFromMin() {
}*/

View file

@ -6,6 +6,9 @@
// is built properly, the end stops are at the correct positions and the axes are perpendicular.
extern const float bed_ref_points[] PROGMEM;
extern const float bed_skew_angle_mild;
extern const float bed_skew_angle_extreme;
// Is the world2machine correction activated?
enum World2MachineCorrectionMode
{
@ -140,8 +143,8 @@ inline bool world2machine_clamp(float &x, float &y)
return clamped;
}
extern bool find_bed_induction_sensor_point_z(float minimum_z = -10.f, uint8_t n_iter = 3);
extern bool find_bed_induction_sensor_point_xy();
extern bool find_bed_induction_sensor_point_z(float minimum_z = -10.f, uint8_t n_iter = 3, int verbosity_level = 0);
extern bool find_bed_induction_sensor_point_xy(int verbosity_level = 0);
extern void go_home_with_z_lift();
// Positive or zero: ok
@ -157,7 +160,7 @@ enum BedSkewOffsetDetectionResultType {
BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME = 2
};
extern BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level);
extern BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level, uint8_t &too_far_mask);
extern BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8_t verbosity_level, uint8_t &too_far_mask);
extern bool sample_mesh_and_store_reference();
@ -178,5 +181,6 @@ extern void babystep_undo();
// Reset the current babystep counter without moving the axes.
extern void babystep_reset();
extern void count_xyz_details();
#endif /* MESH_BED_CALIBRATION_H */

View file

@ -315,9 +315,6 @@
#endif
/*****************************************************************
* EINY Rambo Pin Assignments 0.1a
******************************************************************/
@ -427,7 +424,6 @@
#ifndef KNOWN_BOARD
#error Unknown MOTHERBOARD value in configuration.h
#endif

View file

@ -171,7 +171,9 @@ FORCE_INLINE block_t *plan_get_current_block()
}
// Returns true if the buffer has a queued block, false otherwise
FORCE_INLINE bool blocks_queued() { return (block_buffer_head != block_buffer_tail); }
FORCE_INLINE bool blocks_queued() {
return (block_buffer_head != block_buffer_tail);
}
//return the nr of buffered moves
FORCE_INLINE uint8_t moves_planned() {

View file

@ -33,8 +33,9 @@
#include <SPI.h>
#endif
#ifdef HAVE_TMC2130_DRIVERS
#include <SPI.h>
#endif
#include "tmc2130.h"
#endif //HAVE_TMC2130_DRIVERS
//===========================================================================
//=============================public variables ============================
@ -87,13 +88,8 @@ static bool old_z_max_endstop=false;
#else
static bool check_endstops = true;
#endif
static bool check_z_endstop = false;
static uint8_t sg_homing_axis = 0xFF;
static uint8_t sg_axis_stalled[2] = {0, 0};
static uint8_t sg_lastHomingStalled = false;
int8_t SilentMode;
volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
@ -408,11 +404,6 @@ ISR(TIMER1_COMPA_vect)
{
#if defined(X_MIN_PIN) && X_MIN_PIN > -1
bool x_min_endstop=(READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
#ifdef SG_HOMING
x_min_endstop=false;
#endif
if(sg_homing_axis == X_AXIS && !x_min_endstop)
x_min_endstop = sg_axis_stalled[X_AXIS];
if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
@ -429,8 +420,6 @@ ISR(TIMER1_COMPA_vect)
{
#if defined(X_MAX_PIN) && X_MAX_PIN > -1
bool x_max_endstop=(READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
if(sg_homing_axis == X_AXIS && !x_max_endstop)
x_max_endstop = sg_axis_stalled[X_AXIS];
if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
endstop_x_hit=true;
@ -451,11 +440,6 @@ ISR(TIMER1_COMPA_vect)
{
#if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
bool y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
#ifdef SG_HOMING
y_min_endstop=false;
#endif
if(sg_homing_axis == Y_AXIS && !y_min_endstop)
y_min_endstop = sg_axis_stalled[Y_AXIS];
if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
@ -470,8 +454,6 @@ ISR(TIMER1_COMPA_vect)
{
#if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
bool y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
if(sg_homing_axis == Y_AXIS && !y_max_endstop)
y_max_endstop = sg_axis_stalled[Y_AXIS];
if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
endstop_y_hit=true;
@ -540,12 +522,37 @@ ISR(TIMER1_COMPA_vect)
}
#endif
if ((out_bits & (1<<E_AXIS)) != 0) { // -direction
if ((out_bits & (1 << E_AXIS)) != 0)
{ // -direction
//AKU
#ifdef SNMM
if (snmm_extruder == 0 || snmm_extruder == 2)
{
NORM_E_DIR();
}
else
{
REV_E_DIR();
}
#else
REV_E_DIR();
#endif // SNMM
count_direction[E_AXIS] = -1;
}
else { // +direction
else
{ // +direction
#ifdef SNMM
if (snmm_extruder == 0 || snmm_extruder == 2)
{
REV_E_DIR();
}
else
{
NORM_E_DIR();
}
#else
NORM_E_DIR();
#endif // SNMM
count_direction[E_AXIS] = 1;
}
@ -656,320 +663,13 @@ ISR(TIMER1_COMPA_vect)
}
check_fans();
}
#ifdef HAVE_TMC2130_DRIVERS
uint32_t tmc2130_read(uint8_t chipselect, uint8_t address)
{
uint32_t val32;
uint8_t val0;
uint8_t val1;
uint8_t val2;
uint8_t val3;
uint8_t val4;
//datagram1 - read request (address + dummy write)
SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address);
SPI.transfer(0);
SPI.transfer(0);
SPI.transfer(0);
SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
//datagram2 - response
SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
val0 = SPI.transfer(0);
val1 = SPI.transfer(0);
val2 = SPI.transfer(0);
val3 = SPI.transfer(0);
val4 = SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
#ifdef TMC_DBG_READS
MYSERIAL.print("SPIRead 0x");
MYSERIAL.print(address,HEX);
MYSERIAL.print(" Status:");
MYSERIAL.print(val0 & 0b00000111,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val1,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val2,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val3,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val4,BIN);
#endif
val32 = (uint32_t)val1<<24 | (uint32_t)val2<<16 | (uint32_t)val3<<8 | (uint32_t)val4;
#ifdef TMC_DBG_READS
MYSERIAL.print(" 0x");
MYSERIAL.println(val32,HEX);
#endif
return val32;
}
void tmc2130_write(uint8_t chipselect, uint8_t address,uint8_t wval1,uint8_t wval2,uint8_t wval3,uint8_t wval4)
{
uint32_t val32;
uint8_t val0;
uint8_t val1;
uint8_t val2;
uint8_t val3;
uint8_t val4;
//datagram1 - write
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address+0x80);
SPI.transfer(wval1);
SPI.transfer(wval2);
SPI.transfer(wval3);
SPI.transfer(wval4);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
//datagram2 - response
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
val0 = SPI.transfer(0);
val1 = SPI.transfer(0);
val2 = SPI.transfer(0);
val3 = SPI.transfer(0);
val4 = SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
MYSERIAL.print("WriteRead 0x");
MYSERIAL.print(address,HEX);
MYSERIAL.print(" Status:");
MYSERIAL.print(val0 & 0b00000111,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val1,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val2,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val3,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val4,BIN);
val32 = (uint32_t)val1<<24 | (uint32_t)val2<<16 | (uint32_t)val3<<8 | (uint32_t)val4;
MYSERIAL.print(" 0x");
MYSERIAL.println(val32,HEX);
}
uint8_t tmc2130_read8(uint8_t chipselect, uint8_t address){
//datagram1 - write
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
uint8_t val0;
//datagram2 - response
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
val0 = SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
return val0;
}
uint32_t tmc2130_readRegister(uint8_t chipselect, uint8_t address){
//datagram1 - write
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
uint32_t val0;
//datagram2 - response
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(0); // ignore status bits
val0 = SPI.transfer(0); // MSB
val0 = (val0 << 8) | SPI.transfer(0);
val0 = (val0 << 8) | SPI.transfer(0);
val0 = (val0 << 8) | SPI.transfer(0); //LSB
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
return val0;
}
uint16_t tmc2130_readSG(uint8_t chipselect){
uint8_t address = 0x6F;
uint32_t registerValue = tmc2130_readRegister(chipselect, address);
uint16_t val0 = registerValue & 0x3ff;
return val0;
}
uint16_t tmc2130_readTStep(uint8_t chipselect){
uint8_t address = 0x12;
uint32_t registerValue = tmc2130_readRegister(chipselect, address);
uint16_t val0 = 0;
if(registerValue & 0x000f0000)
val0 = 0xffff;
else
val0 = registerValue & 0xffff;
return val0;
}
void tmc2130_chopconf(uint8_t cs, bool extrapolate256 = 0, uint16_t microstep_resolution = 16)
{
uint8_t mres=0b0100;
if(microstep_resolution == 256) mres = 0b0000;
if(microstep_resolution == 128) mres = 0b0001;
if(microstep_resolution == 64) mres = 0b0010;
if(microstep_resolution == 32) mres = 0b0011;
if(microstep_resolution == 16) mres = 0b0100;
if(microstep_resolution == 8) mres = 0b0101;
if(microstep_resolution == 4) mres = 0b0110;
if(microstep_resolution == 2) mres = 0b0111;
if(microstep_resolution == 1) mres = 0b1000;
mres |= extrapolate256 << 4; //bit28 intpol
//tmc2130_write(cs,0x6C,mres,0x01,0x00,0xD3);
tmc2130_write(cs,0x6C,mres,0x01,0x00,0xC3);
}
void tmc2130_PWMconf(uint8_t cs, uint8_t PWMautoScale = PWM_AUTOSCALE, uint8_t PWMfreq = PWM_FREQ, uint8_t PWMgrad = PWM_GRAD, uint8_t PWMampl = PWM_AMPL)
{
tmc2130_write(cs,0x70,0x00,(PWMautoScale+PWMfreq),PWMgrad,PWMampl); // TMC LJ -> For better readability changed to 0x00 and added PWMautoScale and PWMfreq
}
void tmc2130_PWMthreshold(uint8_t cs)
{
tmc2130_write(cs,0x13,0x00,0x00,0x00,0x00); // TMC LJ -> Adds possibility to swtich from stealthChop to spreadCycle automatically
}
void st_setSGHoming(uint8_t axis){
sg_homing_axis = axis;
}
void st_resetSGflags(){
sg_axis_stalled[X_AXIS] = false;
sg_axis_stalled[Y_AXIS] = false;
}
uint8_t st_didLastHomingStall(){
uint8_t returnValue = sg_lastHomingStalled;
sg_lastHomingStalled = false;
return returnValue;
}
void tmc2130_disable_motor(uint8_t driver)
{
uint8_t cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
tmc2130_write(cs[driver],0x6C,0,01,0,0);
}
void tmc2130_check_overtemp()
{
const static char TMC_OVERTEMP_MSG[] PROGMEM = "TMC DRIVER OVERTEMP ";
uint8_t cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
static uint32_t checktime = 0;
//drivers_disabled[0] = 1; //TEST
if( millis() - checktime > 1000 ) {
for(int i=0;i<4;i++) {
uint32_t drv_status = tmc2130_read(cs[i], 0x6F); //0x6F DRV_STATUS
if(drv_status & ((uint32_t)1<<26)) { // BIT 26 - over temp prewarning ~120C (+-20C)
SERIAL_ERRORRPGM(TMC_OVERTEMP_MSG);
SERIAL_ECHOLN(i);
for(int x=0; x<4;x++) tmc2130_disable_motor(x);
kill(TMC_OVERTEMP_MSG);
}
}
checktime = millis();
}
}
#endif //HAVE_TMC2130_DRIVERS
void tmc2130_init()
{
#ifdef HAVE_TMC2130_DRIVERS
uint8_t cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
uint8_t current[4] = { 31, 31, 31, 31 };
WRITE(X_TMC2130_CS, HIGH);
WRITE(Y_TMC2130_CS, HIGH);
WRITE(Z_TMC2130_CS, HIGH);
WRITE(E0_TMC2130_CS, HIGH);
SET_OUTPUT(X_TMC2130_CS);
SET_OUTPUT(Y_TMC2130_CS);
SET_OUTPUT(Z_TMC2130_CS);
SET_OUTPUT(E0_TMC2130_CS);
SPI.begin();
for(int i=0;i<4;i++)
{
//tmc2130_write(cs[i],0x6C,0b10100,01,00,0xC5);
tmc2130_chopconf(cs[i],1,16);
tmc2130_write(cs[i],0x10,0,15,current[i],current[i]); //0x10 IHOLD_IRUN
//tmc2130_write(cs[i],0x0,0,0,0,0x05); //address=0x0 GCONF EXT VREF
tmc2130_write(cs[i],0x0,0,0,0,0x05); //address=0x0 GCONF EXT VREF - activate stealthChop
//tmc2130_write(cs[i],0x11,0,0,0,0xA);
// Uncomment lines below to use a different configuration (pwm_autoscale = 0) for XY axes
// if(i==0 || i==1)
// tmc2130_PWMconf(cs[i],PWM_AUTOSCALE_XY,PWM_FREQ_XY,PWM_GRAD_XY,PWM_AMPL_XY); //address=0x70 PWM_CONF //reset default=0x00050480
// else
tmc2130_PWMconf(cs[i]); //address=0x70 PWM_CONF //reset default=0x00050480
tmc2130_PWMthreshold(cs[i]);
}
tmc2130_chopconf(cs[3],0,256);
#endif
}
void st_init()
{
tmc2130_init(); //Initialize TMC2130 drivers
#ifdef HAVE_TMC2130_DRIVERS
tmc2130_init();
#endif //HAVE_TMC2130_DRIVERS
digipot_init(); //Initialize Digipot Motor Current
microstep_init(); //Initialize Microstepping Pins
@ -1164,53 +864,14 @@ void st_init()
// Block until all buffered steps are executed
void st_synchronize()
{
uint8_t delay = 0;
while( blocks_queued()) {
manage_heater();
// Vojtech: Don't disable motors inside the planner!
manage_inactivity(true);
lcd_update();
if(sg_homing_axis == X_AXIS || sg_homing_axis == Y_AXIS)
{
uint8_t axis;
if(sg_homing_axis == X_AXIS)
axis = X_TMC2130_CS;
else
axis = Y_TMC2130_CS;
uint16_t tstep = tmc2130_readTStep(axis);
// SERIAL_PROTOCOLLN(tstep);
if(tstep < TCOOLTHRS)
{
if(delay < 255) // wait for a few tens microsteps until stallGuard is used //todo: read out microsteps directly, instead of delay counter
delay++;
else
{
uint16_t sg = tmc2130_readSG(axis);
if(sg==0)
{
sg_axis_stalled[sg_homing_axis] = true;
sg_lastHomingStalled = true;
}
else
sg_axis_stalled[sg_homing_axis] = false;
// SERIAL_PROTOCOLLN(sg);
}
}
else
{
sg_axis_stalled[sg_homing_axis] = false;
delay = 0;
}
}
else
{
sg_axis_stalled[X_AXIS] = false;
sg_axis_stalled[Y_AXIS] = false;
}
#ifdef HAVE_TMC2130_DRIVERS
tmc2130_st_synchronize();
#endif //HAVE_TMC2130_DRIVERS
}
}
@ -1524,3 +1185,4 @@ static void check_fans() {
}
}

View file

@ -105,6 +105,7 @@ uint8_t st_didLastHomingStall();
#endif
#ifdef BABYSTEPPING
void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention
#endif

View file

@ -51,7 +51,12 @@ float current_temperature_bed = 0.0;
int redundant_temperature_raw = 0;
float redundant_temperature = 0.0;
#endif
#ifdef PIDTEMP
float _Kp, _Ki, _Kd;
int pid_cycle, pid_number_of_cycles;
bool pid_tuning_finished = false;
float Kp=DEFAULT_Kp;
float Ki=(DEFAULT_Ki*PID_dT);
float Kd=(DEFAULT_Kd/PID_dT);
@ -183,8 +188,10 @@ unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
void PID_autotune(float temp, int extruder, int ncycles)
{
pid_number_of_cycles = ncycles;
pid_tuning_finished = false;
float input = 0.0;
int cycles=0;
pid_cycle=0;
bool heating = true;
unsigned long temp_millis = millis();
@ -195,7 +202,6 @@ void PID_autotune(float temp, int extruder, int ncycles)
long bias, d;
float Ku, Tu;
float Kp, Ki, Kd;
float max = 0, min = 10000;
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
@ -210,6 +216,8 @@ void PID_autotune(float temp, int extruder, int ncycles)
#endif
){
SERIAL_ECHOLN("PID Autotune failed. Bad extruder number.");
pid_tuning_finished = true;
pid_cycle = 0;
return;
}
@ -267,7 +275,7 @@ void PID_autotune(float temp, int extruder, int ncycles)
heating=true;
t2=millis();
t_low=t2 - t1;
if(cycles > 0) {
if(pid_cycle > 0) {
bias += (d*(t_high - t_low))/(t_low + t_high);
bias = constrain(bias, 20 ,(extruder<0?(MAX_BED_POWER):(PID_MAX))-20);
if(bias > (extruder<0?(MAX_BED_POWER):(PID_MAX))/2) d = (extruder<0?(MAX_BED_POWER):(PID_MAX)) - 1 - bias;
@ -277,33 +285,33 @@ void PID_autotune(float temp, int extruder, int ncycles)
SERIAL_PROTOCOLPGM(" d: "); SERIAL_PROTOCOL(d);
SERIAL_PROTOCOLPGM(" min: "); SERIAL_PROTOCOL(min);
SERIAL_PROTOCOLPGM(" max: "); SERIAL_PROTOCOLLN(max);
if(cycles > 2) {
if(pid_cycle > 2) {
Ku = (4.0*d)/(3.14159*(max-min)/2.0);
Tu = ((float)(t_low + t_high)/1000.0);
SERIAL_PROTOCOLPGM(" Ku: "); SERIAL_PROTOCOL(Ku);
SERIAL_PROTOCOLPGM(" Tu: "); SERIAL_PROTOCOLLN(Tu);
Kp = 0.6*Ku;
Ki = 2*Kp/Tu;
Kd = Kp*Tu/8;
_Kp = 0.6*Ku;
_Ki = 2*_Kp/Tu;
_Kd = _Kp*Tu/8;
SERIAL_PROTOCOLLNPGM(" Classic PID ");
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(Kp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(Ki);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(Kd);
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(_Kp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(_Ki);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(_Kd);
/*
Kp = 0.33*Ku;
Ki = Kp/Tu;
Kd = Kp*Tu/3;
_Kp = 0.33*Ku;
_Ki = _Kp/Tu;
_Kd = _Kp*Tu/3;
SERIAL_PROTOCOLLNPGM(" Some overshoot ");
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(Kp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(Ki);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(Kd);
Kp = 0.2*Ku;
Ki = 2*Kp/Tu;
Kd = Kp*Tu/3;
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(_Kp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(_Ki);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(_Kd);
_Kp = 0.2*Ku;
_Ki = 2*_Kp/Tu;
_Kd = _Kp*Tu/3;
SERIAL_PROTOCOLLNPGM(" No overshoot ");
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(Kp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(Ki);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(Kd);
SERIAL_PROTOCOLPGM(" Kp: "); SERIAL_PROTOCOLLN(_Kp);
SERIAL_PROTOCOLPGM(" Ki: "); SERIAL_PROTOCOLLN(_Ki);
SERIAL_PROTOCOLPGM(" Kd: "); SERIAL_PROTOCOLLN(_Kd);
*/
}
}
@ -311,13 +319,15 @@ void PID_autotune(float temp, int extruder, int ncycles)
soft_pwm_bed = (bias + d) >> 1;
else
soft_pwm[extruder] = (bias + d) >> 1;
cycles++;
pid_cycle++;
min=temp;
}
}
}
if(input > (temp + 20)) {
SERIAL_PROTOCOLLNPGM("PID Autotune failed! Temperature too high");
pid_tuning_finished = true;
pid_cycle = 0;
return;
}
if(millis() - temp_millis > 2000) {
@ -338,10 +348,14 @@ void PID_autotune(float temp, int extruder, int ncycles)
}
if(((millis() - t1) + (millis() - t2)) > (10L*60L*1000L*2L)) {
SERIAL_PROTOCOLLNPGM("PID Autotune failed! timeout");
pid_tuning_finished = true;
pid_cycle = 0;
return;
}
if(cycles > ncycles) {
if(pid_cycle > ncycles) {
SERIAL_PROTOCOLLNPGM("PID Autotune finished! Put the last Kp, Ki and Kd constants from above into Configuration.h");
pid_tuning_finished = true;
pid_cycle = 0;
return;
}
lcd_update();
@ -441,6 +455,7 @@ void fanSpeedError(unsigned char _fan) {
}
}
void checkExtruderAutoFans()
{
uint8_t fanState = 0;
@ -1108,11 +1123,10 @@ void temp_runaway_check(int _heater_id, float _target_temperature, float _curren
float __hysteresis = 0;
int __timeout = 0;
bool temp_runaway_check_active = false;
static float __preheat_start = 0;
static int __preheat_counter = 0;
static int __preheat_errors = 0;
static float __preheat_start[2] = { 0,0}; //currently just bed and one extruder
static int __preheat_counter[2] = { 0,0};
static int __preheat_errors[2] = { 0,0};
_heater_id = (_isbed) ? _heater_id++ : _heater_id;
#ifdef TEMP_RUNAWAY_BED_TIMEOUT
if (_isbed)
@ -1145,8 +1159,8 @@ void temp_runaway_check(int _heater_id, float _target_temperature, float _curren
{
temp_runaway_status[_heater_id] = TempRunaway_PREHEAT;
temp_runaway_target[_heater_id] = _target_temperature;
__preheat_start = _current_temperature;
__preheat_counter = 0;
__preheat_start[_heater_id] = _current_temperature;
__preheat_counter[_heater_id] = 0;
}
else
{
@ -1157,26 +1171,36 @@ void temp_runaway_check(int _heater_id, float _target_temperature, float _curren
if (temp_runaway_status[_heater_id] == TempRunaway_PREHEAT)
{
if (_current_temperature < 150)
if (_current_temperature < ((_isbed) ? (0.8 * _target_temperature) : 150)) //check only in area where temperature is changing fastly for heater, check to 0.8 x target temperature for bed
{
__preheat_counter++;
if (__preheat_counter > 8)
__preheat_counter[_heater_id]++;
if (__preheat_counter[_heater_id] > ((_isbed) ? 16 : 8)) // periodicaly check if current temperature changes
{
if (_current_temperature - __preheat_start < 2) {
__preheat_errors++;
/*SERIAL_ECHOPGM("Heater:");
MYSERIAL.print(_heater_id);
SERIAL_ECHOPGM(" T:");
MYSERIAL.print(_current_temperature);
SERIAL_ECHOPGM(" Tstart:");
MYSERIAL.print(__preheat_start[_heater_id]);*/
if (_current_temperature - __preheat_start[_heater_id] < 2) {
__preheat_errors[_heater_id]++;
/*SERIAL_ECHOPGM(" Preheat errors:");
MYSERIAL.println(__preheat_errors[_heater_id]);*/
}
else {
__preheat_errors = 0;
//SERIAL_ECHOLNPGM("");
__preheat_errors[_heater_id] = 0;
}
if (__preheat_errors > 5)
if (__preheat_errors[_heater_id] > ((_isbed) ? 2 : 5))
{
if (farm_mode) { prusa_statistics(0); }
temp_runaway_stop(true);
temp_runaway_stop(true, _isbed);
if (farm_mode) { prusa_statistics(91); }
}
__preheat_start = _current_temperature;
__preheat_counter = 0;
__preheat_start[_heater_id] = _current_temperature;
__preheat_counter[_heater_id] = 0;
}
}
}
@ -1209,7 +1233,7 @@ void temp_runaway_check(int _heater_id, float _target_temperature, float _curren
if (temp_runaway_error_counter[_heater_id] * 2 > __timeout)
{
if (farm_mode) { prusa_statistics(0); }
temp_runaway_stop(false);
temp_runaway_stop(false, _isbed);
if (farm_mode) { prusa_statistics(90); }
}
}
@ -1219,7 +1243,7 @@ void temp_runaway_check(int _heater_id, float _target_temperature, float _curren
}
}
void temp_runaway_stop(bool isPreheat)
void temp_runaway_stop(bool isPreheat, bool isBed)
{
cancel_heatup = true;
quickStop();
@ -1245,9 +1269,9 @@ void temp_runaway_stop(bool isPreheat)
if (isPreheat)
{
Stop();
LCD_ALERTMESSAGEPGM(" PREHEAT ERROR");
isBed ? LCD_ALERTMESSAGEPGM("BED PREHEAT ERROR") : LCD_ALERTMESSAGEPGM("PREHEAT ERROR");
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(": THERMAL RUNAWAY ( PREHEAT )");
isBed ? SERIAL_ERRORLNPGM(" THERMAL RUNAWAY ( PREHEAT HEATBED)") : SERIAL_ERRORLNPGM(" THERMAL RUNAWAY ( PREHEAT HOTEND)");
SET_OUTPUT(EXTRUDER_0_AUTO_FAN_PIN);
SET_OUTPUT(FAN_PIN);
WRITE(EXTRUDER_0_AUTO_FAN_PIN, 1);
@ -1257,9 +1281,9 @@ void temp_runaway_stop(bool isPreheat)
}
else
{
LCD_ALERTMESSAGEPGM("THERMAL RUNAWAY");
isBed ? LCD_ALERTMESSAGEPGM("BED THERMAL RUNAWAY") : LCD_ALERTMESSAGEPGM("THERMAL RUNAWAY");
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM(": THERMAL RUNAWAY");
isBed ? SERIAL_ERRORLNPGM(" HEATBED THERMAL RUNAWAY") : SERIAL_ERRORLNPGM(" HOTEND THERMAL RUNAWAY");
}
}
#endif
@ -1359,7 +1383,7 @@ void bed_max_temp_error(void) {
}
void bed_min_temp_error(void) {
#if HEATER_BED_PIN > -1
/*#if HEATER_BED_PIN > -1
WRITE(HEATER_BED_PIN, 0);
#endif
if(IsStopped() == false) {
@ -1369,7 +1393,7 @@ void bed_min_temp_error(void) {
}
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
Stop();
#endif
#endif*/
}
#ifdef HEATER_0_USES_MAX6675

View file

@ -58,7 +58,9 @@ extern float current_temperature_bed;
#endif
#ifdef PIDTEMP
extern float Kp,Ki,Kd,Kc;
extern int pid_cycle, pid_number_of_cycles;
extern float Kp,Ki,Kd,Kc,_Kp,_Ki,_Kd;
extern bool pid_tuning_finished;
float scalePID_i(float i);
float scalePID_d(float d);
float unscalePID_i(float i);
@ -180,7 +182,7 @@ static float temp_runaway_timer[4];
static int temp_runaway_error_counter[4];
void temp_runaway_check(int _heater_id, float _target_temperature, float _current_temperature, float _output, bool _isbed);
void temp_runaway_stop(bool isPreheat);
void temp_runaway_stop(bool isPreheat, bool isBed);
#endif
int getHeaterPower(int heater);

View file

@ -1033,7 +1033,9 @@ const short temptable_12[][2] PROGMEM = {
#define PtA 3.9083E-3
#define PtB -5.775E-7
#define PtC -4.183E-12
#define PtRt(T,R0) ((R0)*(1.0+(PtA)*(T)+(PtB)*(T)*(T)))
#define PtRtNew(T,R0) ((R0)*(1.0+(PtA)*(T)+(PtB)*(T)*(T) + (T-100)*PtC*(T)*(T)*(T)))
#define PtAdVal(T,R0,Rup) (short)(1024/(Rup/PtRt(T,R0)+1))
#define PtLine(T,R0,Rup) { PtAdVal(T,R0,Rup)*OVERSAMPLENR, T },
@ -1061,6 +1063,124 @@ const short temptable_147[][2] PROGMEM = {
PtLine(300,100,4700)
};
#endif
// E3D Pt100 with 4k7 MiniRambo pullup, no Amp on the MiniRambo v1.3a
#if (THERMISTORHEATER_0 == 148) || (THERMISTORHEATER_1 == 148) || (THERMISTORHEATER_2 == 148) || (THERMISTORBED == 148)
const short temptable_148[][2] PROGMEM = {
// These values have been calculated and tested over many days. See https://docs.google.com/spreadsheets/d/1MJXa6feEe0mGVCT2TrBwLxVOMoLDkJlvfQ4JXhAdV_E
// Values that are missing from the 5C gap are missing due to resolution limits.
{19.00000 * OVERSAMPLENR, 0},
{19.25000 * OVERSAMPLENR, 5},
{19.50000 * OVERSAMPLENR, 10},
{19.87500 * OVERSAMPLENR, 15},
{20.25000 * OVERSAMPLENR, 20},
{21.00000 * OVERSAMPLENR, 25},
{21.75000 * OVERSAMPLENR, 35},
{22.00000 * OVERSAMPLENR, 40},
{23.00000 * OVERSAMPLENR, 50}, // 55C is more commonly used.
{23.75000 * OVERSAMPLENR, 60},
{24.00000 * OVERSAMPLENR, 65},
{24.06250 * OVERSAMPLENR, 70},
{25.00000 * OVERSAMPLENR, 75},
{25.50000 * OVERSAMPLENR, 85},
{26.00000 * OVERSAMPLENR, 90},
{26.93750 * OVERSAMPLENR,100},
{27.00000 * OVERSAMPLENR,105},
{27.37500 * OVERSAMPLENR,110},
{28.00000 * OVERSAMPLENR,115},
{29.00000 * OVERSAMPLENR,125},
{29.25000 * OVERSAMPLENR,135},
{30.00000 * OVERSAMPLENR,140},
{35.50000 * OVERSAMPLENR,150},
{31.00000 * OVERSAMPLENR,155},
{32.00000 * OVERSAMPLENR,165},
{32.18750 * OVERSAMPLENR,175},
{33.00000 * OVERSAMPLENR,180},
{33.62500 * OVERSAMPLENR,190},
{34.00000 * OVERSAMPLENR,195},
{35.00000 * OVERSAMPLENR,205},
{35.50000 * OVERSAMPLENR,215},
{36.00000 * OVERSAMPLENR,220},
{36.75000 * OVERSAMPLENR,230},
{37.00000 * OVERSAMPLENR,235},
{37.75000 * OVERSAMPLENR,245},
{38.00000 * OVERSAMPLENR,250},
{38.12500 * OVERSAMPLENR,255},
{39.00000 * OVERSAMPLENR,260},
{40.00000 * OVERSAMPLENR,275},
{40.25000 * OVERSAMPLENR,285},
{41.00000 * OVERSAMPLENR,290},
{41.25000 * OVERSAMPLENR,300},
{42.00000 * OVERSAMPLENR,305},
{43.00000 * OVERSAMPLENR,315},
{43.25000 * OVERSAMPLENR,325},
{44.00000 * OVERSAMPLENR,330},
{44.18750 * OVERSAMPLENR,340},
{45.00000 * OVERSAMPLENR,345},
{45.25000 * OVERSAMPLENR,355},
{46.00000 * OVERSAMPLENR,360},
{46.62500 * OVERSAMPLENR,370},
{47.00000 * OVERSAMPLENR,375},
{47.25000 * OVERSAMPLENR,385},
{48.00000 * OVERSAMPLENR,390},
{48.75000 * OVERSAMPLENR,400},
{49.00000 * OVERSAMPLENR,405},
};
#endif
#if (THERMISTORHEATER_0 == 247) || (THERMISTORHEATER_1 == 247) || (THERMISTORHEATER_2 == 247) || (THERMISTORBED == 247) // Pt100 with 4k7 MiniRambo pullup & PT100 Amplifier
const short temptable_247[][2] PROGMEM = {
// Calculated from Bob-the-Kuhn's PT100 calculator listed in https://github.com/MarlinFirmware/Marlin/issues/5543
// and the table provided by E3D at http://wiki.e3d-online.com/wiki/E3D_PT100_Amplifier_Documentation#Output_Characteristics.
{ 0 * OVERSAMPLENR, 0},
{241 * OVERSAMPLENR, 1},
{249 * OVERSAMPLENR, 10},
{259 * OVERSAMPLENR, 20},
{267 * OVERSAMPLENR, 30},
{275 * OVERSAMPLENR, 40},
{283 * OVERSAMPLENR, 50},
{291 * OVERSAMPLENR, 60},
{299 * OVERSAMPLENR, 70},
{307 * OVERSAMPLENR, 80},
{315 * OVERSAMPLENR, 90},
{323 * OVERSAMPLENR, 100},
{331 * OVERSAMPLENR, 110},
{340 * OVERSAMPLENR, 120},
{348 * OVERSAMPLENR, 130},
{354 * OVERSAMPLENR, 140},
{362 * OVERSAMPLENR, 150},
{370 * OVERSAMPLENR, 160},
{378 * OVERSAMPLENR, 170},
{386 * OVERSAMPLENR, 180},
{394 * OVERSAMPLENR, 190},
{402 * OVERSAMPLENR, 200},
{410 * OVERSAMPLENR, 210},
{418 * OVERSAMPLENR, 220},
{426 * OVERSAMPLENR, 230},
{432 * OVERSAMPLENR, 240},
{440 * OVERSAMPLENR, 250},
{448 * OVERSAMPLENR, 260},
{454 * OVERSAMPLENR, 270},
{462 * OVERSAMPLENR, 280},
{469 * OVERSAMPLENR, 290},
{475 * OVERSAMPLENR, 300},
{483 * OVERSAMPLENR, 310},
{491 * OVERSAMPLENR, 320},
{499 * OVERSAMPLENR, 330},
{505 * OVERSAMPLENR, 340},
{513 * OVERSAMPLENR, 350},
{519 * OVERSAMPLENR, 360},
{527 * OVERSAMPLENR, 370},
{533 * OVERSAMPLENR, 380},
{541 * OVERSAMPLENR, 390},
{549 * OVERSAMPLENR, 400},
{616 * OVERSAMPLENR, 500},
{682 * OVERSAMPLENR, 600},
{741 * OVERSAMPLENR, 700},
{801 * OVERSAMPLENR, 800},
{856 * OVERSAMPLENR, 900},
{910 * OVERSAMPLENR, 1000},
{960 * OVERSAMPLENR, 1100},
};
#endif
#if (THERMISTORHEATER_0 == 1010) || (THERMISTORHEATER_1 == 1010) || (THERMISTORHEATER_2 == 1010) || (THERMISTORBED == 1010) // Pt1000 with 1k0 pullup
const short temptable_1010[][2] PROGMEM = {
PtLine(0,1000,1000)

364
Firmware/tmc2130.cpp Normal file
View file

@ -0,0 +1,364 @@
#include "Marlin.h"
#ifdef HAVE_TMC2130_DRIVERS
#include "tmc2130.h"
#include <SPI.h>
uint32_t tmc2130_read(uint8_t chipselect, uint8_t address)
{
uint32_t val32;
uint8_t val0;
uint8_t val1;
uint8_t val2;
uint8_t val3;
uint8_t val4;
//datagram1 - read request (address + dummy write)
SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address);
SPI.transfer(0);
SPI.transfer(0);
SPI.transfer(0);
SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
//datagram2 - response
SPI.beginTransaction(SPISettings(1000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
val0 = SPI.transfer(0);
val1 = SPI.transfer(0);
val2 = SPI.transfer(0);
val3 = SPI.transfer(0);
val4 = SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
#ifdef TMC_DBG_READS
MYSERIAL.print("SPIRead 0x");
MYSERIAL.print(address,HEX);
MYSERIAL.print(" Status:");
MYSERIAL.print(val0 & 0b00000111,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val1,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val2,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val3,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val4,BIN);
#endif
val32 = (uint32_t)val1<<24 | (uint32_t)val2<<16 | (uint32_t)val3<<8 | (uint32_t)val4;
#ifdef TMC_DBG_READS
MYSERIAL.print(" 0x");
MYSERIAL.println(val32,HEX);
#endif
return val32;
}
void tmc2130_write(uint8_t chipselect, uint8_t address,uint8_t wval1,uint8_t wval2,uint8_t wval3,uint8_t wval4)
{
uint32_t val32;
uint8_t val0;
uint8_t val1;
uint8_t val2;
uint8_t val3;
uint8_t val4;
//datagram1 - write
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address+0x80);
SPI.transfer(wval1);
SPI.transfer(wval2);
SPI.transfer(wval3);
SPI.transfer(wval4);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
//datagram2 - response
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
val0 = SPI.transfer(0);
val1 = SPI.transfer(0);
val2 = SPI.transfer(0);
val3 = SPI.transfer(0);
val4 = SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
#ifdef TMC_DBG_WRITE
MYSERIAL.print("WriteRead 0x");
MYSERIAL.print(address,HEX);
MYSERIAL.print(" Status:");
MYSERIAL.print(val0 & 0b00000111,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val1,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val2,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val3,BIN);
MYSERIAL.print(" ");
MYSERIAL.print(val4,BIN);
val32 = (uint32_t)val1<<24 | (uint32_t)val2<<16 | (uint32_t)val3<<8 | (uint32_t)val4;
MYSERIAL.print(" 0x");
MYSERIAL.println(val32,HEX);
#endif //TMC_DBG_READS
}
uint8_t tmc2130_read8(uint8_t chipselect, uint8_t address)
{
//datagram1 - write
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
uint8_t val0;
//datagram2 - response
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
val0 = SPI.transfer(0);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
return val0;
}
uint32_t tmc2130_readRegister(uint8_t chipselect, uint8_t address)
{
//datagram1 - write
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(address);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
SPI.transfer(0x00);
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
uint32_t val0;
//datagram2 - response
SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
digitalWrite(chipselect,LOW);
SPI.transfer(0); // ignore status bits
val0 = SPI.transfer(0); // MSB
val0 = (val0 << 8) | SPI.transfer(0);
val0 = (val0 << 8) | SPI.transfer(0);
val0 = (val0 << 8) | SPI.transfer(0); //LSB
digitalWrite(chipselect, HIGH);
SPI.endTransaction();
return val0;
}
uint16_t tmc2130_readSG(uint8_t chipselect)
{
uint8_t address = 0x6F;
uint32_t registerValue = tmc2130_readRegister(chipselect, address);
uint16_t val0 = registerValue & 0x3ff;
return val0;
}
uint16_t tmc2130_readTStep(uint8_t chipselect)
{
uint8_t address = 0x12;
uint32_t registerValue = tmc2130_readRegister(chipselect, address);
uint16_t val0 = 0;
if(registerValue & 0x000f0000)
val0 = 0xffff;
else
val0 = registerValue & 0xffff;
return val0;
}
void tmc2130_chopconf(uint8_t cs, bool extrapolate256 = 0, uint16_t microstep_resolution = 16)
{
uint8_t mres=0b0100;
if(microstep_resolution == 256) mres = 0b0000;
if(microstep_resolution == 128) mres = 0b0001;
if(microstep_resolution == 64) mres = 0b0010;
if(microstep_resolution == 32) mres = 0b0011;
if(microstep_resolution == 16) mres = 0b0100;
if(microstep_resolution == 8) mres = 0b0101;
if(microstep_resolution == 4) mres = 0b0110;
if(microstep_resolution == 2) mres = 0b0111;
if(microstep_resolution == 1) mres = 0b1000;
mres |= extrapolate256 << 4; //bit28 intpol
//tmc2130_write(cs,0x6C,mres,0x01,0x00,0xD3);
tmc2130_write(cs,0x6C,mres,0x01,0x00,0xC3);
}
void tmc2130_PWMconf(uint8_t cs, uint8_t PWMautoScale = PWM_AUTOSCALE, uint8_t PWMfreq = PWM_FREQ, uint8_t PWMgrad = PWM_GRAD, uint8_t PWMampl = PWM_AMPL)
{
tmc2130_write(cs,0x70,0x00,(PWMautoScale+PWMfreq),PWMgrad,PWMampl); // TMC LJ -> For better readability changed to 0x00 and added PWMautoScale and PWMfreq
}
void tmc2130_PWMthreshold(uint8_t cs)
{
tmc2130_write(cs,0x13,0x00,0x00,0x00,0x00); // TMC LJ -> Adds possibility to swtich from stealthChop to spreadCycle automatically
}
uint8_t st_didLastHomingStall()
{
uint8_t returnValue = sg_lastHomingStalled;
sg_lastHomingStalled = false;
return returnValue;
}
void tmc2130_disable_motor(uint8_t driver)
{
uint8_t cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
tmc2130_write(cs[driver],0x6C,0,01,0,0);
}
void tmc2130_check_overtemp()
{
const static char TMC_OVERTEMP_MSG[] PROGMEM = "TMC DRIVER OVERTEMP ";
uint8_t cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
static uint32_t checktime = 0;
//drivers_disabled[0] = 1; //TEST
if( millis() - checktime > 1000 )
{
for(int i=0;i<4;i++)
{
uint32_t drv_status = tmc2130_read(cs[i], 0x6F); //0x6F DRV_STATUS
if (drv_status & ((uint32_t)1<<26))
{ // BIT 26 - over temp prewarning ~120C (+-20C)
SERIAL_ERRORRPGM(TMC_OVERTEMP_MSG);
SERIAL_ECHOLN(i);
for(int x=0; x<4;x++) tmc2130_disable_motor(x);
kill(TMC_OVERTEMP_MSG);
}
}
checktime = millis();
}
}
void tmc2130_init()
{
uint8_t cs[4] = { X_TMC2130_CS, Y_TMC2130_CS, Z_TMC2130_CS, E0_TMC2130_CS };
// uint8_t current[4] = { 31, 31, 31, 31 };
// uint8_t current_h[4] = { 12, 12, 12, 12 };
// uint8_t current_r[4] = { 24, 24, 24, 24 };
// uint8_t current_r[4] = { 32, 32, 32, 32 };
// uint8_t current_h[4] = { 14, 14, 14, 14 };
uint8_t current_h[4] = { 2, 2, 2, 4 };
uint8_t current_r[4] = { 6, 6, 8, 8 };
WRITE(X_TMC2130_CS, HIGH);
WRITE(Y_TMC2130_CS, HIGH);
WRITE(Z_TMC2130_CS, HIGH);
WRITE(E0_TMC2130_CS, HIGH);
SET_OUTPUT(X_TMC2130_CS);
SET_OUTPUT(Y_TMC2130_CS);
SET_OUTPUT(Z_TMC2130_CS);
SET_OUTPUT(E0_TMC2130_CS);
SPI.begin();
/* for(int i=0;i<4;i++)
{
//tmc2130_write(cs[i],0x6C,0b10100,01,00,0xC5);
tmc2130_chopconf(cs[i],1,16);
tmc2130_write(cs[i],0x10,0,15,current_h[i],current_r[i]); //0x10 IHOLD_IRUN
//tmc2130_write(cs[i],0x0,0,0,0,0x05); //address=0x0 GCONF EXT VREF
tmc2130_write(cs[i],0x0,0,0,0,0x05); //address=0x0 GCONF EXT VREF - activate stealthChop
//tmc2130_write(cs[i],0x11,0,0,0,0xA);
// Uncomment lines below to use a different configuration (pwm_autoscale = 0) for XY axes
if(i==0 || i==1)
tmc2130_PWMconf(cs[i],PWM_AUTOSCALE_XY,PWM_FREQ_XY,PWM_GRAD_XY,PWM_AMPL_XY); //address=0x70 PWM_CONF //reset default=0x00050480
else
tmc2130_PWMconf(cs[i]); //address=0x70 PWM_CONF //reset default=0x00050480
tmc2130_PWMthreshold(cs[i]);
}
*/
#ifdef MK3_TEST1
for (int i=0;i<4;i++)
{
tmc2130_write(cs[i],0x0,0,0,0,0x00); //address=0x0 GCONF - bit 2 activate stealthChop
tmc2130_write(cs[i],0x10,0,15,current_r[i],current_h[i]); //0x10 IHOLD_IRUN
tmc2130_chopconf(cs[i],0,16);
}
#else //MK3_TEST1
for (int i=0;i<3;i++)
{
tmc2130_write(cs[i],0x0,0,0,0,0x04); //address=0x0 GCONF - bit 2 activate stealthChop
tmc2130_write(cs[i],0x10,0,15,current_r[i],current_h[i]); //0x10 IHOLD_IRUN
tmc2130_write(cs[i],0x11,0,0,0,0);
tmc2130_PWMconf(cs[i]); //address=0x70 PWM_CONF //reset default=0x00050480
// tmc2130_PWMthreshold(cs[i]);
tmc2130_chopconf(cs[i],1,16);
}
for (int i=3;i<4;i++)
{
tmc2130_write(cs[i],0x0,0,0,0,0x00); //address=0x0 GCONF - bit 2 activate stealthChop
tmc2130_write(cs[i],0x10,0,15,current_r[i],current_h[i]); //0x10 IHOLD_IRUN
tmc2130_write(cs[i],0x11,0,0,0,0);
tmc2130_chopconf(cs[i],1,16);
}
#endif //MK3_TEST1
}
void tmc2130_st_synchronize()
{
uint8_t delay = 0;
if(sg_homing_axis == X_AXIS || sg_homing_axis == Y_AXIS)
{
uint8_t axis;
if(sg_homing_axis == X_AXIS)
axis = X_TMC2130_CS;
else
axis = Y_TMC2130_CS;
uint16_t tstep = tmc2130_readTStep(axis);
// SERIAL_PROTOCOLLN(tstep);
if(tstep < TCOOLTHRS)
{
if(delay < 255) // wait for a few tens microsteps until stallGuard is used //todo: read out microsteps directly, instead of delay counter
delay++;
else
{
uint16_t sg = tmc2130_readSG(axis);
if(sg==0)
{
sg_axis_stalled[sg_homing_axis] = true;
sg_lastHomingStalled = true;
}
else
sg_axis_stalled[sg_homing_axis] = false;
// SERIAL_PROTOCOLLN(sg);
}
}
else
{
sg_axis_stalled[sg_homing_axis] = false;
delay = 0;
}
}
else
{
sg_axis_stalled[X_AXIS] = false;
sg_axis_stalled[Y_AXIS] = false;
}
}
void tmc2130_st_home_enter(uint8_t axis)
{
sg_homing_axis = axis;
// Configuration to spreadCycle
// tmc2130_write((axis == X_AXIS)? X_TMC2130_CS : Y_TMC2130_CS,0x0,0,0,0,0x01);
tmc2130_write((axis == X_AXIS)? X_TMC2130_CS : Y_TMC2130_CS,0x0,0,0,0,0x00);
tmc2130_write((axis == X_AXIS)? X_TMC2130_CS : Y_TMC2130_CS,0x6D,0,(axis == X_AXIS)?SG_THRESHOLD_X:SG_THRESHOLD_Y,0,0);
tmc2130_write((axis == X_AXIS)? X_TMC2130_CS : Y_TMC2130_CS,0x14,0,0,0,TCOOLTHRS);
}
void tmc2130_st_home_exit()
{
if ((sg_homing_axis == X_AXIS) || (sg_homing_axis == X_AXIS))
{
// Configuration back to stealthChop
tmc2130_write((sg_homing_axis == X_AXIS)? X_TMC2130_CS : Y_TMC2130_CS, 0x0, 0, 0, 0, 0x04);
sg_homing_axis = 0xff;
sg_axis_stalled[X_AXIS] = false;
sg_axis_stalled[Y_AXIS] = false;
}
}
#endif //HAVE_TMC2130_DRIVERS

26
Firmware/tmc2130.h Normal file
View file

@ -0,0 +1,26 @@
#ifndef TMC2130_H
#define TMC2130_H
static uint8_t sg_homing_axis = 0xFF;
static uint8_t sg_axis_stalled[2] = {0, 0};
static uint8_t sg_lastHomingStalled = false;
void tmc2130_check_overtemp();
void tmc2130_write(uint8_t chipselect, uint8_t address,uint8_t wval1,uint8_t wval2,uint8_t wval3,uint8_t wval4);
uint8_t tmc2130_read8(uint8_t chipselect, uint8_t address);
uint16_t tmc2130_readSG(uint8_t chipselect);
uint16_t tmc2130_readTStep(uint8_t chipselect);
void tmc2130_PWMconf(uint8_t cs, uint8_t PWMgrad, uint8_t PWMampl);
uint8_t st_didLastHomingStall();
void tmc2130_st_synchronize();
void tmc2130_st_home_enter(uint8_t axis);
void tmc2130_st_home_exit();
void tmc2130_init();
#endif TMC2130_H

File diff suppressed because it is too large Load diff

View file

@ -91,6 +91,9 @@ void lcd_mylang();
#define LCD_COMMAND_LOAD_FILAMENT 1
#define LCD_COMMAND_STOP_PRINT 2
#define LCD_COMMAND_FARM_MODE_CONFIRM 4
#define LCD_COMMAND_LONG_PAUSE 5
#define LCD_COMMAND_LONG_PAUSE_RESUME 6
#define LCD_COMMAND_PID_EXTRUDER 7
extern unsigned long lcd_timeoutToStatus;
extern int lcd_commands_type;
@ -100,7 +103,12 @@ void lcd_mylang();
extern int farm_timer;
extern int farm_status;
#ifdef SNMM
extern uint8_t snmm_extruder;
#endif // SNMM
extern bool cancel_heatup;
extern bool isPrintPaused;
#ifdef FILAMENT_LCD_DISPLAY
extern unsigned long message_millis;
@ -200,6 +208,7 @@ extern void lcd_implementation_print_at(uint8_t x, uint8_t y, const char *str);
void change_extr(int extr);
static void lcd_colorprint_change();
static int get_ext_nr();
static void extr_adj(int extruder);
static void extr_adj_0();
@ -213,6 +222,10 @@ static void extr_unload_1();
static void extr_unload_2();
static void extr_unload_3();
static void lcd_disable_farm_mode();
void extr_unload_all();
void extr_unload_used();
void extr_unload();
static char snmm_stop_print_menu();
void stack_error();
static void lcd_ping_allert();
@ -233,5 +246,16 @@ void lcd_extr_cal_reset();
union MenuData;
void bowden_menu();
char reset_menu();
char choose_extruder_menu();
void lcd_pinda_calibration_menu();
void lcd_calibrate_pinda();
void lcd_temp_calibration_set();
void display_loading();
void lcd_service_mode_show_result();
#endif //ULTRALCD_H

View file

@ -715,6 +715,7 @@ static void lcd_implementation_status_screen()
lcd.print(itostr3(fan_speed[0]));
lcd.setCursor(8, 1);
lcd.print(itostr3(fan_speed[1]));
#else
//Print Feedrate
lcd.setCursor(LCD_WIDTH - 8-2, 1);
@ -781,15 +782,17 @@ static void lcd_implementation_status_screen()
}
else {
lcd.setCursor(LCD_WIDTH - 8 - 2, 2);
lcd_printPGM(PSTR(" "));
}
#ifdef SNMM
lcd_printPGM(PSTR(" E"));
lcd.print(get_ext_nr() + 1);
#else
lcd.setCursor(LCD_WIDTH - 8 - 2, 2);
lcd_printPGM(PSTR(" "));
#endif
}
//Print time elapsed
lcd.setCursor(LCD_WIDTH - 8 -1, 2);
@ -953,6 +956,39 @@ static void lcd_implementation_status_screen()
{
lcd.print(lcd_status_message);
}
// PID tuning in progress
if (custom_message_type == 3) {
lcd.print(lcd_status_message);
if (pid_cycle <= pid_number_of_cycles && custom_message_state > 0) {
lcd.setCursor(10, 3);
lcd.print(itostr3(pid_cycle));
lcd.print('/');
lcd.print(itostr3left(pid_number_of_cycles));
}
}
// PINDA temp calibration in progress
if (custom_message_type == 4) {
char progress[4];
lcd.setCursor(0, 3);
lcd_printPGM(MSG_TEMP_CALIBRATION);
lcd.setCursor(12, 3);
sprintf(progress, "%d/6", custom_message_state);
lcd.print(progress);
}
// temp compensation preheat
if (custom_message_type == 5) {
lcd.setCursor(0, 3);
lcd_printPGM(MSG_PINDA_PREHEAT);
if (custom_message_state <= PINDA_HEAT_T) {
lcd_printPGM(PSTR(": "));
lcd.print(custom_message_state); //seconds
lcd.print(' ');
}
}
}
else
{

View file

@ -17,7 +17,15 @@
// Electronics
#define MOTHERBOARD BOARD_EINY_0_1a
//#define MOTHERBOARD BOARD_RAMBO_MINI_1_0
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
//#define E3D_PT100_EXTRUDER_WITH_AMP
//#define E3D_PT100_EXTRUDER_NO_AMP
//#define E3D_PT100_BED_WITH_AMP
//#define E3D_PT100_BED_NO_AMP
/*------------------------------------
AXIS SETTINGS
@ -48,6 +56,11 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 190
//Pause print position
#define X_PAUSE_POS 50
#define Y_PAUSE_POS 190
#define Z_PAUSE_LIFT 20
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
@ -86,6 +99,30 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC_DEBUG
// PWM register configuration
#define PWM_GRAD 0x08 // 0x0F - Sets gradient - (max 15 with PWM autoscale activated)
#define PWM_AMPL 0xC8 // 0xFF - Sets PWM amplitude to 200 (max is 255)
#define PWM_AUTOSCALE 0x04 // 0x04 since writing in PWM_CONF (Activates PWM autoscaling)
#define PWM_FREQ 0x01 // 0x01 since writing in PWM_CONF (Sets PWM frequency to 2/683 fCLK)
// Special configuration for XY axes for operation (during standstill, use same settings as for other axes) //todo
#define PWM_GRAD_XY 156 // 0x0F - Sets gradient - (max 15 with PWM autoscale activated)
#define PWM_AMPL_XY 63 // 0xFF - Sets PWM amplitude to 200 (max is 255)
#define PWM_AUTOSCALE_XY 0x00 // 0x04 since writing in PWM_CONF (Activates PWM autoscaling)
#define PWM_FREQ_XY 0x01 // 0x01 since writing in PWM_CONF (Sets PWM frequency to 2/683 fCLK)
#define PWM_THRS 0x00 // TPWM_THRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
#define SG_HOMING 1
#define SG_THRESHOLD_X 8
#define SG_THRESHOLD_Y 8
#define TCOOLTHRS 239
#define TMC_DEBUG
//#define TMC_DBG_READS
//#define TMC_DBG_WRITE
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
@ -97,15 +134,26 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define BED_MINTEMP 15
// Maxtemps
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
#define HEATER_0_MAXTEMP 410
#else
#define HEATER_0_MAXTEMP 305
#endif
#define HEATER_1_MAXTEMP 305
#define HEATER_2_MAXTEMP 305
#define BED_MAXTEMP 150
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
// Define PID constants for extruder with PT100
#define DEFAULT_Kp 21.70
#define DEFAULT_Ki 1.60
#define DEFAULT_Kd 73.76
#else
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
#endif
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
@ -214,7 +262,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define MESH_MEAS_NUM_Y_POINTS 3
#define MESH_HOME_Z_CALIB 0.2
#define MESH_HOME_Z_SEARCH 5
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
@ -250,9 +298,16 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#ifdef PIDTEMPBED
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
// Define PID constants for extruder with PT100
#define DEFAULT_bedKp 21.70
#define DEFAULT_bedKi 1.60
#define DEFAULT_bedKd 73.76
#else
#define DEFAULT_bedKp 126.13
#define DEFAULT_bedKi 4.30
#define DEFAULT_bedKd 924.76
#endif
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
@ -329,12 +384,26 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 148 is E3D Pt100 with 4k7 pullup and no PT100 Amplifier on a MiniRambo 1.3a
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
// 110 is Pt100 with 1k pullup (non standard)
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
#define TEMP_SENSOR_0 247
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
#define TEMP_SENSOR_0 148
#else
#define TEMP_SENSOR_0 5
#endif
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#if defined(E3D_PT100_BED_WITH_AMP)
#define TEMP_SENSOR_BED 247
#elif defined(E3D_PT100_BED_NO_AMP)
#define TEMP_SENSOR_BED 148
#else
#define TEMP_SENSOR_BED 1
#endif
#define STACK_GUARD_TEST_VALUE 0xA2A2
@ -344,16 +413,33 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define MAX_E_STEPS_PER_UNIT 250
#define MIN_E_STEPS_PER_UNIT 100
#define PRINT_STARTED 0xFE
#define PRINT_FINISHED 0xFF
#define Z_BABYSTEP_MIN -3999
#define Z_BABYSTEP_MAX 0
#define PINDA_PREHEAT_X 70
#define PINDA_PREHEAT_Y -3
#define PINDA_PREHEAT_Z 1
#define PINDA_HEAT_T 120 //time in s
#define PINDA_MIN_T 50
#define PINDA_STEP_T 10
#define PINDA_MAX_T 100
#define PING_TIME 60 //time in s
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
#define PING_ALLERT_PERIOD 60 //time in s
#define LONG_PRESS_TIME 1000 //time in ms for button long press
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
#define DEFAULT_PID_TEMP 210
#define MIN_PRINT_FAN_SPEED 50
#ifdef SNMM
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
#else
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
#endif
#endif //__CONFIGURATION_PRUSA_H

View file

@ -18,13 +18,27 @@ GENERAL SETTINGS
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_0
// Prusa Single extruder multiple material suport
//#define SNMM
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
//#define E3D_PT100_EXTRUDER_WITH_AMP
//#define E3D_PT100_EXTRUDER_NO_AMP
//#define E3D_PT100_BED_WITH_AMP
//#define E3D_PT100_BED_NO_AMP
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#ifdef SNMM
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
#else
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,161.3}
#endif
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
@ -48,6 +62,11 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 190
//Pause print position
#define X_PAUSE_POS 50
#define Y_PAUSE_POS 190
#define Z_PAUSE_LIFT 20
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min)
@ -73,15 +92,26 @@ EXTRUDER SETTINGS
#define BED_MINTEMP 15
// Maxtemps
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
#define HEATER_0_MAXTEMP 410
#else
#define HEATER_0_MAXTEMP 305
#endif
#define HEATER_1_MAXTEMP 305
#define HEATER_2_MAXTEMP 305
#define BED_MAXTEMP 150
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
// Define PID constants for extruder with PT100
#define DEFAULT_Kp 21.70
#define DEFAULT_Ki 1.60
#define DEFAULT_Kd 73.76
#else
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
#endif
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
@ -98,13 +128,15 @@ EXTRUDER SETTINGS
#ifdef SNMM
//#define BOWDEN_LENGTH 408
#define BOWDEN_LENGTH 457 //total length for filament fast loading part; max length for extrusion is 465 mm!
#define BOWDEN_LENGTH 433 //default total length for filament fast loading part; max length for extrusion is 465 mm!; this length can be adjusted in service menu
#define FIL_LOAD_LENGTH 102 //length for loading filament into the nozzle
#define FIL_RETURN_LENGTH 30.5 //for filament adjusting (PRUSAY code)
#define FIL_COOLING 10 //length for cooling moves
#define E_MOTOR_LOW_CURRENT 350 // current for PRUSAY code
#define E_MOTOR_HIGH_CURRENT 700 //current for unloading filament, stop print, PRUSAY ramming
#endif //SNMM
//#define DIS //for measuring bed heigth and PINDa detection heigth relative to auto home point, experimental function
#endif
/*------------------------------------
CHANGE FILAMENT SETTINGS
@ -143,8 +175,8 @@ ADDITIONAL FEATURES SETTINGS
#endif
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_BED_HYSTERESIS 5
#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
@ -188,7 +220,7 @@ BED SETTINGS
#define MESH_MEAS_NUM_Y_POINTS 3
#define MESH_HOME_Z_CALIB 0.2
#define MESH_HOME_Z_SEARCH 5
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
@ -224,9 +256,16 @@ BED SETTINGS
#ifdef PIDTEMPBED
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
// Define PID constants for extruder with PT100
#define DEFAULT_bedKp 21.70
#define DEFAULT_bedKi 1.60
#define DEFAULT_bedKd 73.76
#else
#define DEFAULT_bedKp 126.13
#define DEFAULT_bedKi 4.30
#define DEFAULT_bedKd 924.76
#endif
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
@ -303,12 +342,26 @@ THERMISTORS SETTINGS
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 148 is Pt100 with 4k7 pullup and no PT100 Amplifier (in case type 147 doesn't work)
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
// 110 is Pt100 with 1k pullup (non standard)
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
#define TEMP_SENSOR_0 247
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
#define TEMP_SENSOR_0 148
#else
#define TEMP_SENSOR_0 5
#endif
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#if defined(E3D_PT100_BED_WITH_AMP)
#define TEMP_SENSOR_BED 247
#elif defined(E3D_PT100_BED_NO_AMP)
#define TEMP_SENSOR_BED 148
#else
#define TEMP_SENSOR_BED 1
#endif
#define STACK_GUARD_TEST_VALUE 0xA2A2
@ -318,16 +371,31 @@ THERMISTORS SETTINGS
#define MAX_E_STEPS_PER_UNIT 250
#define MIN_E_STEPS_PER_UNIT 100
#define PRINT_STARTED 0xFE
#define PRINT_FINISHED 0xFF
#define Z_BABYSTEP_MIN -3999
#define Z_BABYSTEP_MAX 0
#define PINDA_PREHEAT_X 70
#define PINDA_PREHEAT_Y -3
#define PINDA_PREHEAT_Z 1
#define PINDA_HEAT_T 120 //time in s
#define PINDA_MIN_T 50
#define PINDA_STEP_T 10
#define PINDA_MAX_T 100
#define PING_TIME 60 //time in s
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
#define PING_ALLERT_PERIOD 60 //time in s
#define LONG_PRESS_TIME 1000 //time in ms for button long press
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
#define DEFAULT_PID_TEMP 210
#ifdef SNMM
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
#else
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
#endif
#endif //__CONFIGURATION_PRUSA_H

View file

@ -18,13 +18,27 @@ GENERAL SETTINGS
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_3
// Prusa Single extruder multiple material suport
//#define SNMM
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
//#define E3D_PT100_EXTRUDER_WITH_AMP
//#define E3D_PT100_EXTRUDER_NO_AMP
//#define E3D_PT100_BED_WITH_AMP
//#define E3D_PT100_BED_NO_AMP
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#ifdef SNMM
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
#else
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,161.3}
#endif
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
@ -48,6 +62,11 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 190
//Pause print position
#define X_PAUSE_POS 50
#define Y_PAUSE_POS 190
#define Z_PAUSE_LIFT 20
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min)
@ -73,15 +92,26 @@ EXTRUDER SETTINGS
#define BED_MINTEMP 15
// Maxtemps
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
#define HEATER_0_MAXTEMP 410
#else
#define HEATER_0_MAXTEMP 305
#endif
#define HEATER_1_MAXTEMP 305
#define HEATER_2_MAXTEMP 305
#define BED_MAXTEMP 150
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
// Define PID constants for extruder with PT100
#define DEFAULT_Kp 21.70
#define DEFAULT_Ki 1.60
#define DEFAULT_Kd 73.76
#else
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
#endif
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
@ -93,18 +123,22 @@ EXTRUDER SETTINGS
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
// Prusa Single extruder multiple material suport
//#define SNMM
#ifdef SNMM
//#define BOWDEN_LENGTH 408
#define BOWDEN_LENGTH 457 //total length for filament fast loading part; max length for extrusion is 465 mm!
#define BOWDEN_LENGTH 433 //default total length for filament fast loading part; max length for extrusion is 465 mm!; this length can be adjusted in service menu
#define FIL_LOAD_LENGTH 102 //length for loading filament into the nozzle
#define FIL_RETURN_LENGTH 30.5 //for filament adjusting (PRUSAY code)
#define FIL_COOLING 10 //length for cooling moves
#define E_MOTOR_LOW_CURRENT 350 // current for PRUSAY code
#define E_MOTOR_HIGH_CURRENT 700 //current for unloading filament, stop print, PRUSAY ramming
#endif //SNMM
//#define DIS //for measuring bed heigth and PINDa detection heigth relative to auto home point, experimental function
#endif
/*------------------------------------
CHANGE FILAMENT SETTINGS
@ -143,8 +177,8 @@ ADDITIONAL FEATURES SETTINGS
#endif
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_BED_HYSTERESIS 5
#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
@ -188,7 +222,7 @@ BED SETTINGS
#define MESH_MEAS_NUM_Y_POINTS 3
#define MESH_HOME_Z_CALIB 0.2
#define MESH_HOME_Z_SEARCH 5
#define MESH_HOME_Z_SEARCH 5 //Z lift for homing, mesh bed leveling etc.
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
@ -224,9 +258,16 @@ BED SETTINGS
#ifdef PIDTEMPBED
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#if defined(E3D_PT100_BED_WITH_AMP) || defined(E3D_PT100_BED_NO_AMP)
// Define PID constants for extruder with PT100
#define DEFAULT_bedKp 21.70
#define DEFAULT_bedKi 1.60
#define DEFAULT_bedKd 73.76
#else
#define DEFAULT_bedKp 126.13
#define DEFAULT_bedKi 4.30
#define DEFAULT_bedKd 924.76
#endif
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
@ -303,12 +344,26 @@ THERMISTORS SETTINGS
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 148 is E3D Pt100 with 4k7 pullup and no PT100 Amplifier on a MiniRambo 1.3a
// 247 is Pt100 with 4k7 pullup and PT100 Amplifier
// 110 is Pt100 with 1k pullup (non standard)
#if defined(E3D_PT100_EXTRUDER_WITH_AMP)
#define TEMP_SENSOR_0 247
#elif defined(E3D_PT100_EXTRUDER_NO_AMP)
#define TEMP_SENSOR_0 148
#else
#define TEMP_SENSOR_0 5
#endif
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#if defined(E3D_PT100_BED_WITH_AMP)
#define TEMP_SENSOR_BED 247
#elif defined(E3D_PT100_BED_NO_AMP)
#define TEMP_SENSOR_BED 148
#else
#define TEMP_SENSOR_BED 1
#endif
#define STACK_GUARD_TEST_VALUE 0xA2A2
@ -318,16 +373,31 @@ THERMISTORS SETTINGS
#define MAX_E_STEPS_PER_UNIT 250
#define MIN_E_STEPS_PER_UNIT 100
#define PRINT_STARTED 0xFE
#define PRINT_FINISHED 0xFF
#define Z_BABYSTEP_MIN -3999
#define Z_BABYSTEP_MAX 0
#define PINDA_PREHEAT_X 70
#define PINDA_PREHEAT_Y -3
#define PINDA_PREHEAT_Z 1
#define PINDA_HEAT_T 120 //time in s
#define PINDA_MIN_T 50
#define PINDA_STEP_T 10
#define PINDA_MAX_T 100
#define PING_TIME 60 //time in s
#define PING_TIME_LONG 600 //10 min; used when length of commands buffer > 0 to avoid false triggering when dealing with long gcodes
#define PING_ALLERT_PERIOD 60 //time in s
#define LONG_PRESS_TIME 1000 //time in ms for button long press
#define BUTTON_BLANKING_TIME 200 //time in ms for blanking after button release
#define DEFAULT_PID_TEMP 210
#ifdef SNMM
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
#else
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
#endif
#endif //__CONFIGURATION_PRUSA_H