Merge pull request #553 from XPila/MK3

Mk3 - merged branch MK25
This commit is contained in:
XPila 2018-03-13 20:47:38 +01:00 committed by GitHub
commit a1d917b699
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
54 changed files with 30642 additions and 72575 deletions

View File

@ -132,6 +132,9 @@
// Power loss errors (total)
#define EEPROM_POWER_COUNT_TOT (EEPROM_FERROR_COUNT_TOT - 2) // uint16
#define EEPROM_PRINTER_TYPE (EEPROM_POWER_COUNT_TOT - 2) // uint16
#define EEPROM_BOARD_TYPE (EEPROM_PRINTER_TYPE - 2) // uint16
////////////////////////////////////////
// TMC2130 Accurate sensorless homing
@ -419,12 +422,6 @@ 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_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_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
// ENDSTOP SETTINGS:
// Sets direction of endstops when homing; 1=MAX, -1=MIN
@ -861,8 +858,5 @@ enum CalibrationStatus
#include "Configuration_adv.h"
#include "thermistortables.h"
#define PINDA_THERMISTOR
#define AMBIENT_THERMISTOR
#endif //__CONFIGURATION_H

View File

@ -282,16 +282,6 @@
//#define PROGRESS_MSG_ONCE
#endif
// The hardware watchdog should reset the microcontroller disabling all outputs, in case the firmware gets stuck and doesn't do temperature regulation.
//#define USE_WATCHDOG
#ifdef USE_WATCHDOG
// If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on.
// The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset.
// However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled.
//#define WATCHDOG_RESET_MANUAL
#endif
// Enable the option to stop SD printing when hitting and endstops, needs to be enabled from the LCD menu when this option is enabled.
//#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED

View File

@ -6,6 +6,7 @@
*------------------------------------*/
// Printer revision
#define PRINTER_TYPE PRINTER_MK3
#define FILAMENT_SIZE "1_75mm_MK3"
#define NOZZLE_TYPE "E3Dv6full"
@ -16,7 +17,7 @@
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
// Electronics
#define MOTHERBOARD BOARD_EINSY_0_4a
#define MOTHERBOARD BOARD_EINSY_1_0a
#define HAS_SECOND_SERIAL_PORT
@ -41,6 +42,14 @@ const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Direction inverting
#define INVERT_X_DIR true // 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_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
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS -2.2
@ -101,6 +110,19 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
// Watchdog support
#define WATCHDOG
// Power panic
#define UVLO_SUPPORT
// Fan check
#define FANCHECK
// Safety timer
#define SAFETYTIMER
// Filament sensor
#define PAT9125
// Disable some commands
#define _DISABLE_M42_M226
@ -126,7 +148,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
//#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
//#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
//#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
//#define DEBUG_DISABLE_STARTMSGS //no startup messages
#define DEBUG_DISABLE_STARTMSGS //no startup messages
//#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
//#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
//#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
@ -137,7 +159,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
//#define DEBUG_BLINK_ACTIVE
//#define DEBUG_DISABLE_FANCHECK //disable fan check (no ISR INT7, check disabled)
//#define DEBUG_DISABLE_FSENSORCHECK //disable fsensor check (no ISR INT7, check disabled)
//#define DEBUG_DUMP_TO_2ND_SERIAL //dump received characters to 2nd serial line
#define DEBUG_DUMP_TO_2ND_SERIAL //dump received characters to 2nd serial line
#define DEBUG_STEPPER_TIMER_MISSED // Stop on stepper timer overflow, beep and display a message.
#define PLANNER_DIAGNOSTICS // Show the planner queue status on printer display.
#endif /* DEBUG_BUILD */
@ -268,7 +290,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
#define SAFETYTIMER
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
@ -336,7 +359,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
#if MOTHERBOARD == 200 || MOTHERBOARD == 203
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}

View File

@ -397,9 +397,19 @@ const char* dcode_9_ADC_name(uint8_t i)
extern int current_temperature_raw[EXTRUDERS];
extern int current_temperature_bed_raw;
extern int current_temperature_raw_pinda;
#ifdef AMBIENT_THERMISTOR
extern int current_temperature_raw_ambient;
#endif //AMBIENT_THERMISTOR
#ifdef VOLT_PWR_PIN
extern int current_voltage_raw_pwr;
#endif //VOLT_PWR_PIN
#ifdef VOLT_BED_PIN
extern int current_voltage_raw_bed;
#endif //VOLT_BED_PIN
uint16_t dcode_9_ADC_val(uint8_t i)
{
switch (i)
@ -408,9 +418,15 @@ uint16_t dcode_9_ADC_val(uint8_t i)
case 1: return 0;
case 2: return current_temperature_bed_raw;
case 3: return current_temperature_raw_pinda;
#ifdef VOLT_PWR_PIN
case 4: return current_voltage_raw_pwr;
#endif //VOLT_PWR_PIN
#ifdef AMBIENT_THERMISTOR
case 5: return current_temperature_raw_ambient;
#endif //AMBIENT_THERMISTOR
#ifdef VOLT_BED_PIN
case 6: return current_voltage_raw_bed;
#endif //VOLT_BED_PIN
}
return 0;
}
@ -451,11 +467,11 @@ void dcode_12()
LOG("D12 - Time\n");
}
#include "tmc2130.h"
#include "Marlin.h"
#ifdef TMC2130
#include "planner.h"
extern void st_synchronize();
#include "tmc2130.h"
void dcode_2130()
{
printf_P(PSTR("D2130 - TMC2130\n"));
@ -555,7 +571,9 @@ void dcode_2130()
}
}
}
#endif //TMC2130
#ifdef PAT9125
void dcode_9125()
{
LOG("D9125 - PAT9125\n");
@ -594,5 +612,7 @@ void dcode_9125()
LOG("fsensor_log=%d\n", fsensor_log);
}
}
#endif //PAT9125
#endif //DEBUG_DCODES

View File

@ -16,7 +16,13 @@ extern void dcode_9(); //D9 - Read/Write ADC (Write=enable simulated, Read=disab
extern void dcode_10(); //D10 - XYZ calibration = OK
#ifdef TMC2130
extern void dcode_2130(); //D2130 - TMC2130
#endif //TMC2130
#ifdef PAT9125
extern void dcode_9125(); //D9125 - PAT9125
#endif //PAT9125
#endif //DCODES_H

View File

@ -218,6 +218,7 @@ enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};
void FlushSerialRequestResend();
void ClearToSend();
void update_currents();
void get_coordinates();
void prepare_move();
@ -369,6 +370,7 @@ void temp_compensation_apply();
void temp_compensation_start();
void show_fw_version_warnings();
void erase_eeprom_section(uint16_t offset, uint16_t bytes);
uint8_t check_printer_version();
#ifdef PINDA_THERMISTOR
float temp_compensation_pinda_thermistor_offset(float temperature_pinda);
@ -381,7 +383,10 @@ bool check_commands();
void uvlo_();
void recover_print(uint8_t automatic);
void setup_uvlo_interrupt();
#if defined(TACH_1) && TACH_1 >-1
void setup_fan_interrupt();
#endif
extern void recover_machine_state_after_power_panic();
extern void restore_print_from_eeprom();
@ -430,7 +435,8 @@ void force_high_power_mode(bool start_high_power_section);
#endif //TMC2130
// G-codes
bool gcode_M45(bool onlyZ);
bool gcode_M45(bool onlyZ, int8_t verbosity_level);
void gcode_M114();
void gcode_M701();
#define UVLO !(PINE & (1<<4))

View File

@ -41,6 +41,7 @@
#include "mesh_bed_calibration.h"
#endif
#include "printers.h"
#include "ultralcd.h"
#include "Configuration_prusa.h"
#include "planner.h"
@ -48,7 +49,6 @@
#include "temperature.h"
#include "motion_control.h"
#include "cardreader.h"
#include "watchdog.h"
#include "ConfigurationStore.h"
#include "language.h"
#include "pins_arduino.h"
@ -578,6 +578,9 @@ void restore_print_from_ram_and_continue(float e_move);
bool fans_check_enabled = true;
bool filament_autoload_enabled = true;
#ifdef TMC2130
extern int8_t CrashDetectMenu;
void crashdet_enable()
@ -678,6 +681,7 @@ void crashdet_cancel()
card.closefile();
tmc2130_sg_stop_on_crash = true;
}
#endif //TMC2130
void failstats_reset_print()
{
@ -688,6 +692,7 @@ void failstats_reset_print()
}
#ifdef MESH_BED_LEVELING
enum MeshLevelingState { MeshReport, MeshStart, MeshNext, MeshSet };
#endif
@ -919,7 +924,22 @@ void show_fw_version_warnings() {
lcd_update_enable(true);
}
uint8_t check_printer_version()
{
uint8_t version_changed = 0;
uint16_t printer_type = eeprom_read_word((uint16_t*)EEPROM_PRINTER_TYPE);
uint16_t motherboard = eeprom_read_word((uint16_t*)EEPROM_BOARD_TYPE);
if (printer_type != PRINTER_TYPE) {
if (printer_type == 0xffff) eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
else version_changed |= 0b10;
}
if (motherboard != MOTHERBOARD) {
if(motherboard == 0xffff) eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
else version_changed |= 0b01;
}
return version_changed;
}
void erase_eeprom_section(uint16_t offset, uint16_t bytes)
{
@ -1006,7 +1026,15 @@ void setup()
SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
//lcd_update_enable(false); // why do we need this?? - andre
// loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
bool previous_settings_retrieved = Config_RetrieveSettings(EEPROM_OFFSET);
bool previous_settings_retrieved = false;
uint8_t hw_changed = check_printer_version();
if (!(hw_changed & 0b10)) { //if printer version wasn't changed, check for eeprom version and retrieve settings from eeprom in case that version wasn't changed
previous_settings_retrieved = Config_RetrieveSettings(EEPROM_OFFSET);
}
else { //printer version was changed so use default settings
Config_ResetDefault();
}
SdFatUtil::set_stack_guard(); //writes magic number at the end of static variables to protect against overwriting static memory by stack
tp_init(); // Initialize temperature loop
@ -1014,7 +1042,6 @@ void setup()
lcd_splash(); // we need to do this again, because tp_init() kills lcd
plan_init(); // Initialize planner;
watchdog_init();
factory_reset();
@ -1091,6 +1118,8 @@ void setup()
#endif
setup_homepin();
#ifdef TMC2130
if (1) {
/// SERIAL_ECHOPGM("initial zsteps on power up: "); MYSERIAL.println(tmc2130_rd_MSCNT(Z_AXIS));
// try to run to zero phase before powering the Z motor.
@ -1106,6 +1135,7 @@ void setup()
}
// SERIAL_ECHOPGM("initial zsteps after reset: "); MYSERIAL.println(tmc2130_rd_MSCNT(Z_AXIS));
}
#endif //TMC2130
#if defined(Z_AXIS_ALWAYS_ON)
enable_z();
@ -1121,7 +1151,7 @@ void setup()
// Enable Toshiba FlashAir SD card / WiFi enahanced card.
card.ToshibaFlashAir_enable(eeprom_read_byte((unsigned char*)EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY) == 1);
if (eeprom_read_dword((uint32_t*)(EEPROM_TOP - 4)) == 0x0ffffffff &&
eeprom_read_dword((uint32_t*)(EEPROM_TOP - 8)) == 0x0ffffffff) {
// Maiden startup. The firmware has been loaded and first started on a virgin RAMBo board,
@ -1129,10 +1159,11 @@ void setup()
// Once a firmware boots up, it forces at least a language selection, which changes
// EEPROM_LANG to number lower than 0x0ff.
// 1) Set a high power mode.
#ifdef TMC2130
eeprom_write_byte((uint8_t*)EEPROM_SILENT, 0);
tmc2130_mode = TMC2130_MODE_NORMAL;
#endif //TMC2130
eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 1); //run wizard
}
// Force SD card update. Otherwise the SD card update is done from loop() on card.checkautostart(false),
@ -1231,13 +1262,20 @@ void setup()
}
check_babystep(); //checking if Z babystep is in allowed range
#ifdef UVLO_SUPPORT
setup_uvlo_interrupt();
#ifndef DEBUG_DISABLE_FANCHECK
#endif //UVLO_SUPPORT
#if !defined(DEBUG_DISABLE_FANCHECK) && defined(FANCHECK) && defined(TACH_1) && TACH_1 >-1
setup_fan_interrupt();
#endif //DEBUG_DISABLE_FANCHECK
#ifdef PAT9125
#ifndef DEBUG_DISABLE_FSENSORCHECK
fsensor_setup_interrupt();
#endif //DEBUG_DISABLE_FSENSORCHECK
#endif //PAT9125
for (int i = 0; i<4; i++) EEPROM_read_B(EEPROM_BOWDEN_LENGTH + i * 2, &bowden_length[i]);
#ifndef DEBUG_DISABLE_STARTMSGS
@ -1245,8 +1283,27 @@ void setup()
show_fw_version_warnings();
switch (hw_changed) {
//if motherboard or printer type was changed inform user as it can indicate flashing wrong firmware version
//if user confirms with knob, new hw version (printer and/or motherboard) is written to eeprom and message will be not shown next time
case(0b01):
lcd_show_fullscreen_message_and_wait_P(MSG_CHANGED_MOTHERBOARD);
eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
break;
case(0b10):
lcd_show_fullscreen_message_and_wait_P(MSG_CHANGED_PRINTER);
eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
break;
case(0b11):
lcd_show_fullscreen_message_and_wait_P(MSG_CHANGED_BOTH);
eeprom_write_word((uint16_t*)EEPROM_PRINTER_TYPE, PRINTER_TYPE);
eeprom_write_word((uint16_t*)EEPROM_BOARD_TYPE, MOTHERBOARD);
break;
default: break; //no change, show no message
}
if (!previous_settings_retrieved) {
lcd_show_fullscreen_message_and_wait_P(MSG_DEFAULT_SETTINGS_LOADED); //if EEPROM version was changed, inform user that default setting were loaded
lcd_show_fullscreen_message_and_wait_P(MSG_DEFAULT_SETTINGS_LOADED); //if EEPROM version or printer type was changed, inform user that default setting were loaded
erase_eeprom_section(EEPROM_OFFSET, 156); //erase M500 part of eeprom
}
if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) {
@ -1306,6 +1363,7 @@ void setup()
tmc2130_home_enabled = eeprom_read_byte((uint8_t*)EEPROM_TMC2130_HOME_ENABLED);
if (tmc2130_home_enabled == 0xff) tmc2130_home_enabled = 0;
#ifdef UVLO_SUPPORT
if (eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 1) { //previous print was terminated by UVLO
/*
if (lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_RECOVER_PRINT, false)) recover_print();
@ -1345,8 +1403,12 @@ void setup()
}
}
#endif //UVLO_SUPPORT
KEEPALIVE_STATE(NOT_BUSY);
#ifdef WATCHDOG
wdt_enable(WDTO_4S);
#endif //WATCHDOG
}
#ifdef PAT9125
@ -2162,7 +2224,7 @@ void force_high_power_mode(bool start_high_power_section) {
}
#endif //TMC2130
bool gcode_M45(bool onlyZ)
bool gcode_M45(bool onlyZ, int8_t verbosity_level)
{
bool final_result = false;
#ifdef TMC2130
@ -2212,15 +2274,19 @@ bool gcode_M45(bool onlyZ)
{
#endif //TMC2130
refresh_cmd_timeout();
//if (((degHotend(0) > MAX_HOTEND_TEMP_CALIBRATION) || (degBed() > MAX_BED_TEMP_CALIBRATION)) && (!onlyZ))
//{
// lcd_wait_for_cool_down();
//}
#ifndef STEEL_SHEET
if (((degHotend(0) > MAX_HOTEND_TEMP_CALIBRATION) || (degBed() > MAX_BED_TEMP_CALIBRATION)) && (!onlyZ))
{
lcd_wait_for_cool_down();
}
#endif //STEEL_SHEET
if(!onlyZ)
{
KEEPALIVE_STATE(PAUSED_FOR_USER);
#ifdef STEEL_SHEET
bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(MSG_STEEL_SHEET_CHECK, false, false);
if(result) lcd_show_fullscreen_message_and_wait_P(MSG_REMOVE_STEEL_SHEET);
#endif //STEEL_SHEET
lcd_show_fullscreen_message_and_wait_P(MSG_CONFIRM_NOZZLE_CLEAN);
lcd_show_fullscreen_message_and_wait_P(MSG_PAPER);
KEEPALIVE_STATE(IN_HANDLER);
@ -2232,20 +2298,21 @@ bool gcode_M45(bool onlyZ)
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
bool endstops_enabled = enable_endstops(true);
#ifdef TMC2130
tmc2130_home_enter(Z_AXIS_MASK);
#endif //TMC2130
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder);
st_synchronize();
#ifdef TMC2130
tmc2130_home_exit();
#endif //TMC2130
enable_endstops(endstops_enabled);
if (st_get_position_mm(Z_AXIS) == MESH_HOME_Z_SEARCH)
{
//#ifdef TMC2130
// tmc2130_home_enter(X_AXIS_MASK | Y_AXIS_MASK);
//#endif
int8_t verbosity_level = 0;
if (code_seen('V'))
{
@ -2289,6 +2356,9 @@ bool gcode_M45(bool onlyZ)
#ifndef NEW_XYZCAL
if (result >= 0)
{
#ifdef HEATBED_V2
sample_z();
#else //HEATBED_V2
point_too_far_mask = 0;
// Second half: The fine adjustment.
// Let the planner use the uncorrected coordinates.
@ -2303,7 +2373,8 @@ bool gcode_M45(bool onlyZ)
current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder);
st_synchronize();
// if (result >= 0) babystep_apply();
// if (result >= 0) babystep_apply();
#endif //HEATBED_V2
}
#endif //NEW_XYZCAL
@ -2337,6 +2408,29 @@ bool gcode_M45(bool onlyZ)
return final_result;
}
void gcode_M114()
{
SERIAL_PROTOCOLPGM("X:");
SERIAL_PROTOCOL(current_position[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y:");
SERIAL_PROTOCOL(current_position[Y_AXIS]);
SERIAL_PROTOCOLPGM(" Z:");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL(current_position[E_AXIS]);
SERIAL_PROTOCOLRPGM(MSG_COUNT_X);
SERIAL_PROTOCOL(float(st_get_position(X_AXIS)) / axis_steps_per_unit[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y:");
SERIAL_PROTOCOL(float(st_get_position(Y_AXIS)) / axis_steps_per_unit[Y_AXIS]);
SERIAL_PROTOCOLPGM(" Z:");
SERIAL_PROTOCOL(float(st_get_position(Z_AXIS)) / axis_steps_per_unit[Z_AXIS]);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL(float(st_get_position(E_AXIS)) / axis_steps_per_unit[E_AXIS]);
SERIAL_PROTOCOLLN("");
}
void gcode_M701()
{
#ifdef SNMM
@ -2420,6 +2514,7 @@ void process_commands()
lcd_setstatus(strchr_pointer + 5);
}
#ifdef TMC2130
else if(code_seen("CRASH_DETECTED"))
{
uint8_t mask = 0;
@ -2431,6 +2526,7 @@ void process_commands()
crashdet_recover();
else if(code_seen("CRASH_CANCEL"))
crashdet_cancel();
#endif //TMC2130
else if(code_seen("PRUSA")){
if (code_seen("Ping")) { //PRUSA Ping
@ -4280,8 +4376,17 @@ void process_commands()
case 45: // M45: Prusa3D: bed skew and offset with manual Z up
{
int8_t verbosity_level = 0;
bool only_Z = code_seen('Z');
gcode_M45(only_Z);
#ifdef SUPPORT_VERBOSITY
if (code_seen('V'))
{
// Just 'V' without a number counts as V1.
char c = strchr_pointer[1];
verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short();
}
#endif //SUPPORT_VERBOSITY
gcode_M45(only_Z, verbosity_level);
}
break;
@ -4977,25 +5082,7 @@ Sigma_Exit:
lcd_setstatus(strchr_pointer + 5);
break;*/
case 114: // M114
SERIAL_PROTOCOLPGM("X:");
SERIAL_PROTOCOL(current_position[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y:");
SERIAL_PROTOCOL(current_position[Y_AXIS]);
SERIAL_PROTOCOLPGM(" Z:");
SERIAL_PROTOCOL(current_position[Z_AXIS]);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL(current_position[E_AXIS]);
SERIAL_PROTOCOLRPGM(MSG_COUNT_X);
SERIAL_PROTOCOL(float(st_get_position(X_AXIS))/axis_steps_per_unit[X_AXIS]);
SERIAL_PROTOCOLPGM(" Y:");
SERIAL_PROTOCOL(float(st_get_position(Y_AXIS))/axis_steps_per_unit[Y_AXIS]);
SERIAL_PROTOCOLPGM(" Z:");
SERIAL_PROTOCOL(float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]);
SERIAL_PROTOCOLPGM(" E:");
SERIAL_PROTOCOL(float(st_get_position(E_AXIS))/axis_steps_per_unit[E_AXIS]);
SERIAL_PROTOCOLLN("");
gcode_M114();
break;
case 120: // M120
enable_endstops(false) ;
@ -5595,8 +5682,10 @@ Sigma_Exit:
#ifdef FILAMENTCHANGEENABLE
case 600: //Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
{
#ifdef PAT9125
bool old_fsensor_enabled = fsensor_enabled;
fsensor_enabled = false; //temporary solution for unexpected restarting
#endif //PAT9125
st_synchronize();
float target[4];
@ -5816,8 +5905,16 @@ Sigma_Exit:
target[E_AXIS] -= FILAMENTCHANGE_FINALRETRACT;
st_synchronize();
#ifdef TMC2130
uint8_t tmc2130_current_r_bckp = tmc2130_current_r[E_AXIS];
tmc2130_set_current_r(E_AXIS, TMC2130_UNLOAD_CURRENT_R);
#else
digipot_current(2, 200); //set lower E motor current for unload to protect filament sensor and ptfe tube
float tmp_motor[3] = DEFAULT_PWM_MOTOR_CURRENT;
float tmp_motor_loud[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD;
#endif //TMC2130
target[E_AXIS] -= 45;
plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 5200 / 60, active_extruder);
@ -5828,8 +5925,15 @@ Sigma_Exit:
target[E_AXIS] -= 20;
plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], 1000 / 60, active_extruder);
st_synchronize();
#ifdef TMC2130
tmc2130_set_current_r(E_AXIS, tmc2130_current_r_bckp);
#else
uint8_t silentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT);
if(silentMode) digipot_current(2, tmp_motor[2]); //set E back to normal operation currents
else digipot_current(2, tmp_motor_loud[2]);
#endif //TMC2130
#endif // SNMM
@ -5864,6 +5968,7 @@ Sigma_Exit:
lcd_wait_interact();
//load_filament_time = millis();
KEEPALIVE_STATE(PAUSED_FOR_USER);
#ifdef PAT9125
if (filament_autoload_enabled && (old_fsensor_enabled || fsensor_M600)) fsensor_autoload_check_start();
#endif //PAT9125
@ -5894,6 +5999,7 @@ Sigma_Exit:
//WRITE(BEEPER, LOW);
KEEPALIVE_STATE(IN_HANDLER);
#ifdef SNMM
display_loading();
KEEPALIVE_STATE(PAUSED_FOR_USER);
@ -6032,9 +6138,8 @@ Sigma_Exit:
custom_message = false;
custom_message_type = 0;
fsensor_enabled = old_fsensor_enabled; //temporary solution for unexpected restarting
#ifdef PAT9125
fsensor_enabled = old_fsensor_enabled; //temporary solution for unexpected restarting
if (fsensor_M600)
{
@ -6105,6 +6210,8 @@ Sigma_Exit:
}
break;
#ifdef TMC2130
case 910: // M910 TMC2130 init
{
tmc2130_init();
@ -6184,6 +6291,8 @@ Sigma_Exit:
}
break;
#endif //TMC2130
case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
{
#ifdef TMC2130
@ -6256,8 +6365,10 @@ Sigma_Exit:
extr_unload_all(); //unload all filaments
}
#else
#ifdef PAT9125
bool old_fsensor_enabled = fsensor_enabled;
fsensor_enabled = false;
#endif //PAT9125
custom_message = true;
custom_message_type = 2;
lcd_setstatuspgm(MSG_UNLOADING_FILAMENT);
@ -6299,7 +6410,9 @@ Sigma_Exit:
lcd_setstatuspgm(WELCOME_MSG);
custom_message = false;
custom_message_type = 0;
#ifdef PAT9125
fsensor_enabled = old_fsensor_enabled;
#endif //PAT9125
#endif
}
break;
@ -6462,10 +6575,17 @@ Sigma_Exit:
case 10: // D10 - XYZ calibration = OK
dcode_10(); break;
#ifdef TMC2130
case 2130: // D9125 - TMC2130
dcode_2130(); break;
#endif //TMC2130
#ifdef PAT9125
case 9125: // D9125 - PAT9125
dcode_9125(); break;
#endif //PAT9125
}
}
#endif //DEBUG_DCODES
@ -6500,6 +6620,45 @@ void ClearToSend()
SERIAL_PROTOCOLLNRPGM(MSG_OK);
}
#if MOTHERBOARD == 200 || MOTHERBOARD == 203
void update_currents() {
float current_high[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD;
float current_low[3] = DEFAULT_PWM_MOTOR_CURRENT;
float tmp_motor[3];
//SERIAL_ECHOLNPGM("Currents updated: ");
if (destination[Z_AXIS] < Z_SILENT) {
//SERIAL_ECHOLNPGM("LOW");
for (uint8_t i = 0; i < 3; i++) {
digipot_current(i, current_low[i]);
/*MYSERIAL.print(int(i));
SERIAL_ECHOPGM(": ");
MYSERIAL.println(current_low[i]);*/
}
}
else if (destination[Z_AXIS] > Z_HIGH_POWER) {
//SERIAL_ECHOLNPGM("HIGH");
for (uint8_t i = 0; i < 3; i++) {
digipot_current(i, current_high[i]);
/*MYSERIAL.print(int(i));
SERIAL_ECHOPGM(": ");
MYSERIAL.println(current_high[i]);*/
}
}
else {
for (uint8_t i = 0; i < 3; i++) {
float q = current_low[i] - Z_SILENT*((current_high[i] - current_low[i]) / (Z_HIGH_POWER - Z_SILENT));
tmp_motor[i] = ((current_high[i] - current_low[i]) / (Z_HIGH_POWER - Z_SILENT))*destination[Z_AXIS] + q;
digipot_current(i, tmp_motor[i]);
/*MYSERIAL.print(int(i));
SERIAL_ECHOPGM(": ");
MYSERIAL.println(tmp_motor[i]);*/
}
}
}
#endif //MOTHERBOARD == 200 || MOTHERBOARD == 203
void get_coordinates()
{
bool seen[4]={false,false,false,false};
@ -6521,6 +6680,9 @@ void get_coordinates()
if (relative)
destination[i] += current_position[i];
seen[i]=true;
#if MOTHERBOARD == 200 || MOTHERBOARD == 203
if (i == Z_AXIS && SilentModeMenu == 2) update_currents();
#endif //MOTHERBOARD == 200 || MOTHERBOARD == 203
}
else destination[i] = current_position[i]; //Are these else lines really needed?
}
@ -6743,7 +6905,9 @@ void handle_status_leds(void) {
*/
static void handleSafetyTimer()
{
static_assert(EXTRUDERS == 1,"Implemented only for one extruder.");
#if (EXTRUDERS > 1)
#error Implemented only for one extruder.
#endif //(EXTRUDERS > 1)
static Timer safetyTimer;
if (IS_SD_PRINTING || is_usb_printing || (custom_message_type == 4) || (lcd_commands_type == LCD_COMMAND_V2_CAL) ||
(!degTargetBed() && !degTargetHotend(0)))
@ -6764,6 +6928,7 @@ static void handleSafetyTimer()
void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h
{
#ifdef PAT9125
if (fsensor_enabled && filament_autoload_enabled && !fsensor_M600 && !moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LCD_COMMAND_V2_CAL))
{
if (fsensor_autoload_enabled)
@ -6801,6 +6966,12 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s
else
if (fsensor_autoload_enabled)
fsensor_autoload_check_stop();
#endif //PAT9125
#ifdef SAFETYTIMER
handleSafetyTimer();
#endif //SAFETYTIMER
#ifdef SAFETYTIMER
handleSafetyTimer();
@ -6929,7 +7100,9 @@ void kill(const char *full_screen_message, unsigned char id)
suicide();
while(1)
{
wdt_reset();
#ifdef WATCHDOG
wdt_reset();
#endif //WATCHDOG
/* Intentionally left empty */
} // Wait for reset
@ -7595,6 +7768,8 @@ void serialecho_temperatures() {
extern uint32_t sdpos_atomic;
#ifdef UVLO_SUPPORT
void uvlo_()
{
unsigned long time_start = millis();
@ -7604,10 +7779,12 @@ void uvlo_()
disable_y();
disable_e0();
#ifdef TMC2130
tmc2130_set_current_h(Z_AXIS, 20);
tmc2130_set_current_r(Z_AXIS, 20);
tmc2130_set_current_h(E_AXIS, 20);
tmc2130_set_current_r(E_AXIS, 20);
#endif //TMC2130
// Indicate that the interrupt has been triggered.
@ -7615,7 +7792,10 @@ void uvlo_()
// Read out the current Z motor microstep counter. This will be later used
// for reaching the zero full step before powering off.
uint16_t z_microsteps = tmc2130_rd_MSCNT(Z_AXIS);
uint16_t z_microsteps = 0;
#ifdef TMC2130
z_microsteps = tmc2130_rd_MSCNT(Z_TMC2130_CS);
#endif //TMC2130
// Calculate the file position, from which to resume this print.
long sd_position = sdpos_atomic; //atomic sd position of last command added in queue
@ -7744,6 +7924,9 @@ void uvlo_()
};
}
#endif //UVLO_SUPPORT
#if (defined(FANCHECK) && defined(TACH_1) && (TACH_1 >-1))
void setup_fan_interrupt() {
//INT7
@ -7775,6 +7958,9 @@ ISR(INT7_vect) {
EICRB ^= (1 << 6); //change edge
}
#endif
#ifdef UVLO_SUPPORT
void setup_uvlo_interrupt() {
DDRE &= ~(1 << 4); //input pin
PORTE &= ~(1 << 4); //no internal pull-up
@ -7984,6 +8170,7 @@ void restore_print_from_eeprom() {
// Start SD print.
enquecommand_P(PSTR("M24"));
}
#endif //UVLO_SUPPORT
////////////////////////////////////////////////////////////////////////////////

29
Firmware/MenuStack.cpp Normal file
View File

@ -0,0 +1,29 @@
/**
* @file
* @author Marek Bel
*/
#include "MenuStack.h"
/**
* @brief Push menu on stack
* @param menu
* @param position selected position in menu being pushed
*/
void MenuStack::push(menuFunc_t menu, uint8_t position)
{
if (m_index >= max_depth) return;
m_stack[m_index].menu = menu;
m_stack[m_index].position = position;
++m_index;
}
/**
* @brief Pop menu from stack
* @return Record containing menu function pointer and previously selected line number
*/
MenuStack::Record MenuStack::pop()
{
if (m_index != 0) m_index--;
return m_stack[m_index];
}

34
Firmware/MenuStack.h Normal file
View File

@ -0,0 +1,34 @@
/**
* @file
* @author Marek Bel
*/
#ifndef MENUSTACK_H
#define MENUSTACK_H
#include <stdint.h>
/** Pointer to function implementing menu.*/
typedef void (*menuFunc_t)();
/**
* @brief Stack implementation for navigating menu structure
*/
class MenuStack
{
public:
struct Record
{
menuFunc_t menu;
uint8_t position;
};
MenuStack():m_stack(),m_index(0) {}
void push(menuFunc_t menu, uint8_t position);
Record pop();
void reset(){m_index = 0;}
private:
static const int max_depth = 4;
Record m_stack[max_depth];
uint8_t m_index;
};
#endif /* FIRMWARE_MENUSTACK_H_ */

View File

@ -3,14 +3,10 @@
#define BOARD_UNKNOWN -1
#define BOARD_RAMBO 100 // Rambo - 100 (orig 301)
#define BOARD_RAMBO_MINI_1_0 200 // Rambo-mini 1.0 - 200 (orig 102)
#define BOARD_RAMBO_MINI_1_3 203 // Rambo-mini 1.3 - 203 (orig 302)
#define BOARD_EISNY_0_3a 303 // EINY 0.3a - 303 (orig 300)
#define BOARD_EINSY_0_4a 304 // EINY 0.4a - 304 (orig 299)
#define BOARD_EINSY_0_5a 305 // EINY 0.5a - 305 (orig 298)
#define BOARD_EINSY_1_0a 310 // EINSy 1.0a - 310 (new)
#define MB(board) (MOTHERBOARD==BOARD_##board)
#define IS_RAMPS (MB(RAMPS_OLD) || MB(RAMPS_13_EFB) || MB(RAMPS_13_EEB) || MB(RAMPS_13_EFF) || MB(RAMPS_13_EEF))

View File

@ -60,6 +60,11 @@ const char * const MSG_AUTO_HOME_LANG_TABLE[1] PROGMEM = {
MSG_AUTO_HOME_EN
};
const char MSG_AUTO_MODE_ON_EN[] PROGMEM = "Mode [auto power]";
const char * const MSG_AUTO_MODE_ON_LANG_TABLE[1] PROGMEM = {
MSG_AUTO_MODE_ON_EN
};
const char MSG_A_RETRACT_EN[] PROGMEM = "A-retract";
const char * const MSG_A_RETRACT_LANG_TABLE[1] PROGMEM = {
MSG_A_RETRACT_EN
@ -320,6 +325,27 @@ const char * const MSG_CARD_MENU_LANG_TABLE[LANG_NUM] PROGMEM = {
MSG_CARD_MENU_CZ
};
const char MSG_CHANGED_BOTH_EN[] PROGMEM = "Warning: both printer type and motherboard type changed.";
const char MSG_CHANGED_BOTH_CZ[] PROGMEM = "Varovani: doslo ke zmene typu tiskarny a motherboardu.";
const char * const MSG_CHANGED_BOTH_LANG_TABLE[LANG_NUM] PROGMEM = {
MSG_CHANGED_BOTH_EN,
MSG_CHANGED_BOTH_CZ
};
const char MSG_CHANGED_MOTHERBOARD_EN[] PROGMEM = "Warning: motherboard type changed.";
const char MSG_CHANGED_MOTHERBOARD_CZ[] PROGMEM = "Varovani: doslo ke zmene typu motherboardu.";
const char * const MSG_CHANGED_MOTHERBOARD_LANG_TABLE[LANG_NUM] PROGMEM = {
MSG_CHANGED_MOTHERBOARD_EN,
MSG_CHANGED_MOTHERBOARD_CZ
};
const char MSG_CHANGED_PRINTER_EN[] PROGMEM = "Warning: printer type changed.";
const char MSG_CHANGED_PRINTER_CZ[] PROGMEM = "Varovani: doslo ke zmene typu tiskarny.";
const char * const MSG_CHANGED_PRINTER_LANG_TABLE[LANG_NUM] PROGMEM = {
MSG_CHANGED_PRINTER_EN,
MSG_CHANGED_PRINTER_CZ
};
const char MSG_CHANGE_EXTR_EN[] PROGMEM = "Change extruder";
const char MSG_CHANGE_EXTR_CZ[] PROGMEM = "Zmenit extruder";
const char * const MSG_CHANGE_EXTR_LANG_TABLE[LANG_NUM] PROGMEM = {
@ -1966,14 +1992,14 @@ const char * const MSG_SHOW_END_STOPS_LANG_TABLE[LANG_NUM] PROGMEM = {
MSG_SHOW_END_STOPS_CZ
};
const char MSG_SILENT_MODE_OFF_EN[] PROGMEM = "Mode [Normal]";
const char MSG_SILENT_MODE_OFF_EN[] PROGMEM = "Mode [high power]";
const char MSG_SILENT_MODE_OFF_CZ[] PROGMEM = "Mod [Normal]";
const char * const MSG_SILENT_MODE_OFF_LANG_TABLE[LANG_NUM] PROGMEM = {
MSG_SILENT_MODE_OFF_EN,
MSG_SILENT_MODE_OFF_CZ
};
const char MSG_SILENT_MODE_ON_EN[] PROGMEM = "Mode [Stealth]";
const char MSG_SILENT_MODE_ON_EN[] PROGMEM = "Mode [silent]";
const char MSG_SILENT_MODE_ON_CZ[] PROGMEM = "Mod [Stealth]";
const char * const MSG_SILENT_MODE_ON_LANG_TABLE[LANG_NUM] PROGMEM = {
MSG_SILENT_MODE_ON_EN,

View File

@ -40,6 +40,8 @@ extern const char* const MSG_AUTOLOAD_FILAMENT_LANG_TABLE[LANG_NUM];
#define MSG_AUTOLOAD_FILAMENT LANG_TABLE_SELECT(MSG_AUTOLOAD_FILAMENT_LANG_TABLE)
extern const char* const MSG_AUTO_HOME_LANG_TABLE[1];
#define MSG_AUTO_HOME LANG_TABLE_SELECT_EXPLICIT(MSG_AUTO_HOME_LANG_TABLE, 0)
extern const char* const MSG_AUTO_MODE_ON_LANG_TABLE[1];
#define MSG_AUTO_MODE_ON LANG_TABLE_SELECT_EXPLICIT(MSG_AUTO_MODE_ON_LANG_TABLE, 0)
extern const char* const MSG_A_RETRACT_LANG_TABLE[1];
#define MSG_A_RETRACT LANG_TABLE_SELECT_EXPLICIT(MSG_A_RETRACT_LANG_TABLE, 0)
extern const char* const MSG_BABYSTEPPING_X_LANG_TABLE[1];
@ -120,6 +122,12 @@ 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_CHANGED_BOTH_LANG_TABLE[LANG_NUM];
#define MSG_CHANGED_BOTH LANG_TABLE_SELECT(MSG_CHANGED_BOTH_LANG_TABLE)
extern const char* const MSG_CHANGED_MOTHERBOARD_LANG_TABLE[LANG_NUM];
#define MSG_CHANGED_MOTHERBOARD LANG_TABLE_SELECT(MSG_CHANGED_MOTHERBOARD_LANG_TABLE)
extern const char* const MSG_CHANGED_PRINTER_LANG_TABLE[LANG_NUM];
#define MSG_CHANGED_PRINTER LANG_TABLE_SELECT(MSG_CHANGED_PRINTER_LANG_TABLE)
extern const char* const MSG_CHANGE_EXTR_LANG_TABLE[LANG_NUM];
#define MSG_CHANGE_EXTR LANG_TABLE_SELECT(MSG_CHANGE_EXTR_LANG_TABLE)
extern const char* const MSG_CHANGE_SUCCESS_LANG_TABLE[LANG_NUM];

View File

@ -407,3 +407,6 @@
#define MSG_FW_VERSION_BETA "Pouzivate beta verzi firmwaru. Jedna se o vyvojovou verzi. Pouzivani teto verze firmware neni doporuceno a muze zpusobit poskozeni tiskarny."
#define MSG_FW_VERSION_RC "Tato verze firmware je release candidate. Nektere z funkci nemusi pracovat spolehlive."
#define MSG_FORCE_SELFTEST "Pro kalibraci presneho rehomovani bude nyni spusten selftest."
#define MSG_CHANGED_MOTHERBOARD "Varovani: doslo ke zmene typu motherboardu."
#define MSG_CHANGED_PRINTER "Varovani: doslo ke zmene typu tiskarny."
#define MSG_CHANGED_BOTH "Varovani: doslo ke zmene typu tiskarny a motherboardu."

View File

@ -102,8 +102,9 @@
#define(length=20) MSG_CHANGING_FILAMENT "Changing filament!"
#define MSG_SILENT_MODE_ON "Mode [Stealth]"
#define MSG_SILENT_MODE_OFF "Mode [Normal]"
#define MSG_SILENT_MODE_ON "Mode [silent]"
#define MSG_SILENT_MODE_OFF "Mode [high power]"
#define MSG_AUTO_MODE_ON "Mode [auto power]"
#define(length=20) MSG_REBOOT "Reboot the printer"
#define(length=20) MSG_TAKE_EFFECT " for take effect"
@ -413,3 +414,6 @@
#define(length=20, lines=8) MSG_FW_VERSION_BETA "You are using firmware beta version. This is development version. Using this version is not recommended and may cause printer damage."
#define(length=20, lines=8) MSG_FW_VERSION_RC "This firmware version is release candidate. Some of the features may not work properly."
#define(length=20, lines=8) MSG_FORCE_SELFTEST "Selftest will be run to calibrate accurate sensorless rehoming."
#define(length=20, lines=4) MSG_CHANGED_MOTHERBOARD "Warning: motherboard type changed."
#define(length=20, lines=4) MSG_CHANGED_PRINTER "Warning: printer type changed."
#define(length=20, lines=4) MSG_CHANGED_BOTH "Warning: both printer type and motherboard type changed."

View File

@ -56,10 +56,10 @@ 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 the following: center front, center right, center rear, center left.
const float bed_ref_points_4[] PROGMEM = {
13.f - BED_ZERO_REF_X, 10.4f - BED_ZERO_REF_Y,
221.f - BED_ZERO_REF_X, 10.4f - BED_ZERO_REF_Y,
221.f - BED_ZERO_REF_X, 202.4f - BED_ZERO_REF_Y,
13.f - BED_ZERO_REF_X, 202.4f - BED_ZERO_REF_Y
13.f - BED_ZERO_REF_X, 10.4f - 4.f - BED_ZERO_REF_Y,
221.f - BED_ZERO_REF_X, 10.4f - 4.f - BED_ZERO_REF_Y,
221.f - BED_ZERO_REF_X, 202.4f - 4.f - BED_ZERO_REF_Y,
13.f - BED_ZERO_REF_X, 202.4f - 4.f - BED_ZERO_REF_Y
};
const float bed_ref_points[] PROGMEM = {
@ -104,10 +104,17 @@ const float bed_ref_points[] PROGMEM = {
static inline float sqr(float x) { return x * x; }
#ifdef HEATBED_V2
static inline bool point_on_1st_row(const uint8_t i)
{
return (i < 2);
return false;
}
#else //HEATBED_V2
static inline bool point_on_1st_row(const uint8_t i)
{
return (i < 3);
}
#endif //HEATBED_V2
// Weight of a point coordinate in a least squares optimization.
// The first row of points may not be fully reachable
@ -905,27 +912,34 @@ extern bool xyzcal_find_bed_induction_sensor_point_xy();
// look for the induction sensor response.
// Adjust the current_position[X,Y,Z] to the center of the target dot and its response Z coordinate.
#define FIND_BED_INDUCTION_SENSOR_POINT_X_RADIUS (8.f)
#define FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS (6.f)
#define FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS (4.f)
#define FIND_BED_INDUCTION_SENSOR_POINT_XY_STEP (1.f)
#ifdef HEATBED_V2
#define FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP (2.f)
#define FIND_BED_INDUCTION_SENSOR_POINT_MAX_Z_ERROR (0.03f)
#else //HEATBED_V2
#define FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP (0.2f)
#endif //HEATBED_V2
#ifdef HEATBED_V2
/*inline */bool find_bed_induction_sensor_point_xy(int verbosity_level)
{
#ifdef NEW_XYZCAL
return xyzcal_find_bed_induction_sensor_point_xy();
#else //NEW_XYZCAL
#ifdef SUPPORT_VERBOSITY
if(verbosity_level >= 10) MYSERIAL.println("find bed induction sensor point xy");
if (verbosity_level >= 10) MYSERIAL.println("find bed induction sensor point xy");
#endif // SUPPORT_VERBOSITY
float feedrate = homing_feedrate[X_AXIS] / 60.f;
bool found = false;
bool found = false;
{
float x0 = current_position[X_AXIS] - FIND_BED_INDUCTION_SENSOR_POINT_X_RADIUS;
float x1 = current_position[X_AXIS] + FIND_BED_INDUCTION_SENSOR_POINT_X_RADIUS;
float y0 = current_position[Y_AXIS] - FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS;
float y1 = current_position[Y_AXIS] + FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS;
uint8_t nsteps_y;
uint8_t i;
{
float x0 = current_position[X_AXIS] - FIND_BED_INDUCTION_SENSOR_POINT_X_RADIUS;
float x1 = current_position[X_AXIS] + FIND_BED_INDUCTION_SENSOR_POINT_X_RADIUS;
float y0 = current_position[Y_AXIS] - FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS;
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) {
x0 = X_MIN_POS;
#ifdef SUPPORT_VERBOSITY
@ -950,163 +964,411 @@ extern bool xyzcal_find_bed_induction_sensor_point_xy();
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("Y searching radius higher than X_MAX. Clamping was done.");
#endif // SUPPORT_VERBOSITY
}
nsteps_y = int(ceil((y1 - y0) / FIND_BED_INDUCTION_SENSOR_POINT_XY_STEP));
nsteps_y = int(ceil((y1 - y0) / FIND_BED_INDUCTION_SENSOR_POINT_XY_STEP));
enable_endstops(false);
bool dir_positive = true;
enable_endstops(false);
bool dir_positive = true;
float z_error = 2 * FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP;
float find_bed_induction_sensor_point_z_step = FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP;
float initial_z_position = current_position[Z_AXIS];
// go_xyz(current_position[X_AXIS], current_position[Y_AXIS], MESH_HOME_Z_SEARCH, homing_feedrate[Z_AXIS]/60);
go_xyz(x0, y0, current_position[Z_AXIS], feedrate);
// Continously lower the Z axis.
endstops_hit_on_purpose();
enable_z_endstop(true);
while (current_position[Z_AXIS] > -10.f) {
// Do nsteps_y zig-zag movements.
current_position[Y_AXIS] = y0;
for (i = 0; i < nsteps_y; current_position[Y_AXIS] += (y1 - y0) / float(nsteps_y - 1), ++ i) {
// Run with a slightly decreasing Z axis, zig-zag movement. Stop at the Z end-stop.
current_position[Z_AXIS] -= FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP / float(nsteps_y);
go_xyz(dir_positive ? x1 : x0, current_position[Y_AXIS], current_position[Z_AXIS], feedrate);
dir_positive = ! dir_positive;
if (endstop_z_hit_on_purpose())
goto endloop;
}
for (i = 0; i < nsteps_y; current_position[Y_AXIS] -= (y1 - y0) / float(nsteps_y - 1), ++ i) {
// Run with a slightly decreasing Z axis, zig-zag movement. Stop at the Z end-stop.
current_position[Z_AXIS] -= FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP / float(nsteps_y);
go_xyz(dir_positive ? x1 : x0, current_position[Y_AXIS], current_position[Z_AXIS], feedrate);
dir_positive = ! dir_positive;
if (endstop_z_hit_on_purpose())
goto endloop;
}
}
endloop:
// SERIAL_ECHOLN("First hit");
// go_xyz(current_position[X_AXIS], current_position[Y_AXIS], MESH_HOME_Z_SEARCH, homing_feedrate[Z_AXIS]/60);
go_xyz(x0, y0, current_position[Z_AXIS], feedrate);
// Continously lower the Z axis.
endstops_hit_on_purpose();
enable_z_endstop(true);
bool direction = false;
while (current_position[Z_AXIS] > -10.f && z_error > FIND_BED_INDUCTION_SENSOR_POINT_MAX_Z_ERROR) {
// Do nsteps_y zig-zag movements.
// we have to let the planner know where we are right now as it is not where we said to go.
update_current_position_xyz();
SERIAL_ECHOPGM("z_error: ");
MYSERIAL.println(z_error);
current_position[Y_AXIS] = direction ? y1 : y0;
initial_z_position = current_position[Z_AXIS];
for (i = 0; i < (nsteps_y - 1); (direction == false) ? (current_position[Y_AXIS] += (y1 - y0) / float(nsteps_y - 1)) : (current_position[Y_AXIS] -= (y1 - y0) / float(nsteps_y - 1)), ++i) {
// Run with a slightly decreasing Z axis, zig-zag movement. Stop at the Z end-stop.
current_position[Z_AXIS] -= find_bed_induction_sensor_point_z_step / float(nsteps_y - 1);
go_xyz(dir_positive ? x1 : x0, current_position[Y_AXIS], current_position[Z_AXIS], feedrate);
dir_positive = !dir_positive;
if (endstop_z_hit_on_purpose()) {
update_current_position_xyz();
z_error = initial_z_position - current_position[Z_AXIS] + find_bed_induction_sensor_point_z_step;
if (z_error > FIND_BED_INDUCTION_SENSOR_POINT_MAX_Z_ERROR) {
find_bed_induction_sensor_point_z_step = z_error / 2;
current_position[Z_AXIS] += z_error;
enable_z_endstop(false);
(direction == false) ? go_xyz(x0, y0, current_position[Z_AXIS], feedrate) : go_xyz(x0, y1, current_position[Z_AXIS], feedrate);
enable_z_endstop(true);
}
goto endloop;
}
}
for (i = 0; i < (nsteps_y - 1); (direction == false) ? (current_position[Y_AXIS] -= (y1 - y0) / float(nsteps_y - 1)) : (current_position[Y_AXIS] += (y1 - y0) / float(nsteps_y - 1)), ++i) {
// Run with a slightly decreasing Z axis, zig-zag movement. Stop at the Z end-stop.
current_position[Z_AXIS] -= find_bed_induction_sensor_point_z_step / float(nsteps_y - 1);
go_xyz(dir_positive ? x1 : x0, current_position[Y_AXIS], current_position[Z_AXIS], feedrate);
dir_positive = !dir_positive;
if (endstop_z_hit_on_purpose()) {
update_current_position_xyz();
z_error = initial_z_position - current_position[Z_AXIS];
if (z_error > FIND_BED_INDUCTION_SENSOR_POINT_MAX_Z_ERROR) {
find_bed_induction_sensor_point_z_step = z_error / 2;
current_position[Z_AXIS] += z_error;
enable_z_endstop(false);
direction = !direction;
(direction == false) ? go_xyz(x0, y0, current_position[Z_AXIS], feedrate) : go_xyz(x0, y1, current_position[Z_AXIS], feedrate);
enable_z_endstop(true);
}
goto endloop;
}
}
endloop:;
}
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) {
SERIAL_ECHO("First hit");
SERIAL_ECHO("- X: ");
MYSERIAL.print(current_position[X_AXIS]);
SERIAL_ECHO("; Y: ");
MYSERIAL.print(current_position[Y_AXIS]);
SERIAL_ECHO("; Z: ");
MYSERIAL.println(current_position[Z_AXIS]);
}
#endif //SUPPORT_VERBOSITY
//lcd_show_fullscreen_message_and_wait_P(PSTR("First hit"));
//lcd_update_enable(true);
// Search in this plane for the first hit. Zig-zag first in X, then in Y axis.
for (int8_t iter = 0; iter < 3; ++ iter) {
if (iter > 0) {
// Slightly lower the Z axis to get a reliable trigger.
current_position[Z_AXIS] -= 0.02f;
go_xyz(current_position[X_AXIS], current_position[Y_AXIS], MESH_HOME_Z_SEARCH, homing_feedrate[Z_AXIS]/60);
}
float init_x_position = current_position[X_AXIS];
float init_y_position = current_position[Y_AXIS];
// Do nsteps_y zig-zag movements.
float a, b;
enable_endstops(false);
enable_z_endstop(false);
current_position[Y_AXIS] = y0;
go_xy(x0, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
found = false;
for (i = 0, dir_positive = true; i < nsteps_y; current_position[Y_AXIS] += (y1 - y0) / float(nsteps_y - 1), ++ i, dir_positive = ! dir_positive) {
go_xy(dir_positive ? x1 : x0, current_position[Y_AXIS], feedrate);
if (endstop_z_hit_on_purpose()) {
found = true;
break;
}
}
update_current_position_xyz();
if (! found) {
// SERIAL_ECHOLN("Search in Y - not found");
continue;
}
// SERIAL_ECHOLN("Search in Y - found");
a = current_position[Y_AXIS];
// we have to let the planner know where we are right now as it is not where we said to go.
update_current_position_xyz();
enable_z_endstop(false);
for (int8_t iter = 0; iter < 2; ++iter) {
/*SERIAL_ECHOPGM("iter: ");
MYSERIAL.println(iter);
SERIAL_ECHOPGM("1 - current_position[Z_AXIS]: ");
MYSERIAL.println(current_position[Z_AXIS]);*/
enable_z_endstop(false);
current_position[Y_AXIS] = y1;
go_xy(x0, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
found = false;
for (i = 0, dir_positive = true; i < nsteps_y; current_position[Y_AXIS] -= (y1 - y0) / float(nsteps_y - 1), ++ i, dir_positive = ! dir_positive) {
go_xy(dir_positive ? x1 : x0, current_position[Y_AXIS], feedrate);
if (endstop_z_hit_on_purpose()) {
found = true;
break;
}
}
update_current_position_xyz();
if (! found) {
// SERIAL_ECHOLN("Search in Y2 - not found");
continue;
}
// SERIAL_ECHOLN("Search in Y2 - found");
b = current_position[Y_AXIS];
current_position[Y_AXIS] = 0.5f * (a + b);
// Slightly lower the Z axis to get a reliable trigger.
current_position[Z_AXIS] -= 0.1f;
go_xyz(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], homing_feedrate[Z_AXIS] / (60 * 10));
// Search in the X direction along a cross.
found = false;
enable_z_endstop(false);
go_xy(x0, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
go_xy(x1, current_position[Y_AXIS], feedrate);
update_current_position_xyz();
if (! endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search X span 0 - not found");
continue;
}
// SERIAL_ECHOLN("Search X span 0 - found");
a = current_position[X_AXIS];
enable_z_endstop(false);
go_xy(x1, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
go_xy(x0, current_position[Y_AXIS], feedrate);
update_current_position_xyz();
if (! endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search X span 1 - not found");
continue;
}
// SERIAL_ECHOLN("Search X span 1 - found");
b = current_position[X_AXIS];
// Go to the center.
enable_z_endstop(false);
current_position[X_AXIS] = 0.5f * (a + b);
go_xy(current_position[X_AXIS], current_position[Y_AXIS], feedrate);
found = true;
SERIAL_ECHOPGM("2 - current_position[Z_AXIS]: ");
MYSERIAL.println(current_position[Z_AXIS]);
// Do nsteps_y zig-zag movements.
float a, b;
float avg[2] = { 0,0 };
invert_z_endstop(true);
for (int iteration = 0; iteration < 8; iteration++) {
#if 1
// Search in the Y direction along a cross.
found = false;
enable_z_endstop(false);
go_xy(current_position[X_AXIS], y0, feedrate);
enable_z_endstop(true);
go_xy(current_position[X_AXIS], y1, feedrate);
update_current_position_xyz();
if (! endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search Y2 span 0 - not found");
continue;
}
// SERIAL_ECHOLN("Search Y2 span 0 - found");
a = current_position[Y_AXIS];
enable_z_endstop(false);
go_xy(current_position[X_AXIS], y1, feedrate);
enable_z_endstop(true);
go_xy(current_position[X_AXIS], y0, feedrate);
update_current_position_xyz();
if (! endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search Y2 span 1 - not found");
continue;
}
// SERIAL_ECHOLN("Search Y2 span 1 - found");
b = current_position[Y_AXIS];
// Go to the center.
enable_z_endstop(false);
current_position[Y_AXIS] = 0.5f * (a + b);
go_xy(current_position[X_AXIS], current_position[Y_AXIS], feedrate);
found = true;
#endif
break;
}
}
found = false;
enable_z_endstop(true);
go_xy(init_x_position + 16.0f, current_position[Y_AXIS], feedrate / 5);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search X span 0 - not found");
continue;
}
// SERIAL_ECHOLN("Search X span 0 - found");
a = current_position[X_AXIS];
enable_z_endstop(false);
go_xy(init_x_position, current_position[Y_AXIS], feedrate / 5);
enable_z_endstop(true);
go_xy(init_x_position - 16.0f, current_position[Y_AXIS], feedrate / 5);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search X span 1 - not found");
continue;
}
// SERIAL_ECHOLN("Search X span 1 - found");
b = current_position[X_AXIS];
// Go to the center.
enable_z_endstop(false);
current_position[X_AXIS] = 0.5f * (a + b);
go_xy(current_position[X_AXIS], init_y_position, feedrate / 5);
found = true;
// Search in the Y direction along a cross.
found = false;
enable_z_endstop(true);
go_xy(current_position[X_AXIS], init_y_position + 16.0f, feedrate / 5);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search Y2 span 0 - not found");
continue;
}
// SERIAL_ECHOLN("Search Y2 span 0 - found");
a = current_position[Y_AXIS];
enable_z_endstop(false);
go_xy(current_position[X_AXIS], init_y_position, feedrate / 5);
enable_z_endstop(true);
go_xy(current_position[X_AXIS], init_y_position - 16.0f, feedrate / 5);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search Y2 span 1 - not found");
continue;
}
// SERIAL_ECHOLN("Search Y2 span 1 - found");
b = current_position[Y_AXIS];
// Go to the center.
enable_z_endstop(false);
current_position[Y_AXIS] = 0.5f * (a + b);
go_xy(current_position[X_AXIS], current_position[Y_AXIS], feedrate / 5);
enable_z_endstop(false);
return found;
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) {
SERIAL_ECHOPGM("ITERATION: ");
MYSERIAL.println(iteration);
SERIAL_ECHOPGM("CURRENT POSITION X: ");
MYSERIAL.println(current_position[X_AXIS]);
SERIAL_ECHOPGM("CURRENT POSITION Y: ");
MYSERIAL.println(current_position[Y_AXIS]);
}
#endif //SUPPORT_VERBOSITY
if (iteration > 0) {
// Average the last 7 measurements.
avg[X_AXIS] += current_position[X_AXIS];
avg[Y_AXIS] += current_position[Y_AXIS];
}
init_x_position = current_position[X_AXIS];
init_y_position = current_position[Y_AXIS];
found = true;
}
invert_z_endstop(false);
avg[X_AXIS] *= (1.f / 7.f);
avg[Y_AXIS] *= (1.f / 7.f);
current_position[X_AXIS] = avg[X_AXIS];
current_position[Y_AXIS] = avg[Y_AXIS];
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) {
SERIAL_ECHOPGM("AVG CURRENT POSITION X: ");
MYSERIAL.println(current_position[X_AXIS]);
SERIAL_ECHOPGM("AVG CURRENT POSITION Y: ");
MYSERIAL.println(current_position[Y_AXIS]);
}
#endif // SUPPORT_VERBOSITY
go_xy(current_position[X_AXIS], current_position[Y_AXIS], feedrate);
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) {
lcd_show_fullscreen_message_and_wait_P(PSTR("Final position"));
lcd_update_enable(true);
}
#endif //SUPPORT_VERBOSITY
break;
}
}
enable_z_endstop(false);
invert_z_endstop(false);
return found;
#endif //NEW_XYZCAL
}
#else //HEATBED_V2
inline bool find_bed_induction_sensor_point_xy(int verbosity_level)
{
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 10) MYSERIAL.println("find bed induction sensor point xy");
#endif // SUPPORT_VERBOSITY
float feedrate = homing_feedrate[X_AXIS] / 60.f;
bool found = false;
{
float x0 = current_position[X_AXIS] - FIND_BED_INDUCTION_SENSOR_POINT_X_RADIUS;
float x1 = current_position[X_AXIS] + FIND_BED_INDUCTION_SENSOR_POINT_X_RADIUS;
float y0 = current_position[Y_AXIS] - FIND_BED_INDUCTION_SENSOR_POINT_Y_RADIUS;
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) {
x0 = X_MIN_POS;
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("X searching radius lower than X_MIN. Clamping was done.");
#endif // SUPPORT_VERBOSITY
}
if (x1 > X_MAX_POS) {
x1 = X_MAX_POS;
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("X searching radius higher than X_MAX. Clamping was done.");
#endif // SUPPORT_VERBOSITY
}
if (y0 < Y_MIN_POS_FOR_BED_CALIBRATION) {
y0 = Y_MIN_POS_FOR_BED_CALIBRATION;
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("Y searching radius lower than Y_MIN. Clamping was done.");
#endif // SUPPORT_VERBOSITY
}
if (y1 > Y_MAX_POS) {
y1 = Y_MAX_POS;
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 20) SERIAL_ECHOLNPGM("Y searching radius higher than X_MAX. Clamping was done.");
#endif // SUPPORT_VERBOSITY
}
nsteps_y = int(ceil((y1 - y0) / FIND_BED_INDUCTION_SENSOR_POINT_XY_STEP));
enable_endstops(false);
bool dir_positive = true;
// go_xyz(current_position[X_AXIS], current_position[Y_AXIS], MESH_HOME_Z_SEARCH, homing_feedrate[Z_AXIS]/60);
go_xyz(x0, y0, current_position[Z_AXIS], feedrate);
// Continously lower the Z axis.
endstops_hit_on_purpose();
enable_z_endstop(true);
while (current_position[Z_AXIS] > -10.f) {
// Do nsteps_y zig-zag movements.
current_position[Y_AXIS] = y0;
for (i = 0; i < nsteps_y; current_position[Y_AXIS] += (y1 - y0) / float(nsteps_y - 1), ++i) {
// Run with a slightly decreasing Z axis, zig-zag movement. Stop at the Z end-stop.
current_position[Z_AXIS] -= FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP / float(nsteps_y);
go_xyz(dir_positive ? x1 : x0, current_position[Y_AXIS], current_position[Z_AXIS], feedrate);
dir_positive = !dir_positive;
if (endstop_z_hit_on_purpose())
goto endloop;
}
for (i = 0; i < nsteps_y; current_position[Y_AXIS] -= (y1 - y0) / float(nsteps_y - 1), ++i) {
// Run with a slightly decreasing Z axis, zig-zag movement. Stop at the Z end-stop.
current_position[Z_AXIS] -= FIND_BED_INDUCTION_SENSOR_POINT_Z_STEP / float(nsteps_y);
go_xyz(dir_positive ? x1 : x0, current_position[Y_AXIS], current_position[Z_AXIS], feedrate);
dir_positive = !dir_positive;
if (endstop_z_hit_on_purpose())
goto endloop;
}
}
endloop:
// SERIAL_ECHOLN("First hit");
// we have to let the planner know where we are right now as it is not where we said to go.
update_current_position_xyz();
// Search in this plane for the first hit. Zig-zag first in X, then in Y axis.
for (int8_t iter = 0; iter < 3; ++iter) {
if (iter > 0) {
// Slightly lower the Z axis to get a reliable trigger.
current_position[Z_AXIS] -= 0.02f;
go_xyz(current_position[X_AXIS], current_position[Y_AXIS], MESH_HOME_Z_SEARCH, homing_feedrate[Z_AXIS] / 60);
}
// Do nsteps_y zig-zag movements.
float a, b;
enable_endstops(false);
enable_z_endstop(false);
current_position[Y_AXIS] = y0;
go_xy(x0, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
found = false;
for (i = 0, dir_positive = true; i < nsteps_y; current_position[Y_AXIS] += (y1 - y0) / float(nsteps_y - 1), ++i, dir_positive = !dir_positive) {
go_xy(dir_positive ? x1 : x0, current_position[Y_AXIS], feedrate);
if (endstop_z_hit_on_purpose()) {
found = true;
break;
}
}
update_current_position_xyz();
if (!found) {
// SERIAL_ECHOLN("Search in Y - not found");
continue;
}
// SERIAL_ECHOLN("Search in Y - found");
a = current_position[Y_AXIS];
enable_z_endstop(false);
current_position[Y_AXIS] = y1;
go_xy(x0, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
found = false;
for (i = 0, dir_positive = true; i < nsteps_y; current_position[Y_AXIS] -= (y1 - y0) / float(nsteps_y - 1), ++i, dir_positive = !dir_positive) {
go_xy(dir_positive ? x1 : x0, current_position[Y_AXIS], feedrate);
if (endstop_z_hit_on_purpose()) {
found = true;
break;
}
}
update_current_position_xyz();
if (!found) {
// SERIAL_ECHOLN("Search in Y2 - not found");
continue;
}
// SERIAL_ECHOLN("Search in Y2 - found");
b = current_position[Y_AXIS];
current_position[Y_AXIS] = 0.5f * (a + b);
// Search in the X direction along a cross.
found = false;
enable_z_endstop(false);
go_xy(x0, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
go_xy(x1, current_position[Y_AXIS], feedrate);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search X span 0 - not found");
continue;
}
// SERIAL_ECHOLN("Search X span 0 - found");
a = current_position[X_AXIS];
enable_z_endstop(false);
go_xy(x1, current_position[Y_AXIS], feedrate);
enable_z_endstop(true);
go_xy(x0, current_position[Y_AXIS], feedrate);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search X span 1 - not found");
continue;
}
// SERIAL_ECHOLN("Search X span 1 - found");
b = current_position[X_AXIS];
// Go to the center.
enable_z_endstop(false);
current_position[X_AXIS] = 0.5f * (a + b);
go_xy(current_position[X_AXIS], current_position[Y_AXIS], feedrate);
found = true;
#if 1
// Search in the Y direction along a cross.
found = false;
enable_z_endstop(false);
go_xy(current_position[X_AXIS], y0, feedrate);
enable_z_endstop(true);
go_xy(current_position[X_AXIS], y1, feedrate);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search Y2 span 0 - not found");
continue;
}
// SERIAL_ECHOLN("Search Y2 span 0 - found");
a = current_position[Y_AXIS];
enable_z_endstop(false);
go_xy(current_position[X_AXIS], y1, feedrate);
enable_z_endstop(true);
go_xy(current_position[X_AXIS], y0, feedrate);
update_current_position_xyz();
if (!endstop_z_hit_on_purpose()) {
// SERIAL_ECHOLN("Search Y2 span 1 - not found");
continue;
}
// SERIAL_ECHOLN("Search Y2 span 1 - found");
b = current_position[Y_AXIS];
// Go to the center.
enable_z_endstop(false);
current_position[Y_AXIS] = 0.5f * (a + b);
go_xy(current_position[X_AXIS], current_position[Y_AXIS], feedrate);
found = true;
#endif
break;
}
}
enable_z_endstop(false);
return found;
}
#endif //HEATBED_V2
#ifndef NEW_XYZCAL
// Search around the current_position[X,Y,Z].
@ -1382,7 +1644,7 @@ canceled:
// Searching in a zig-zag movement in a plane for the maximum width of the response.
// This function may set the current_position[Y_AXIS] below Y_MIN_POS, if the function succeeded.
// If this function failed, the Y coordinate will never be outside the working space.
#define IMPROVE_BED_INDUCTION_SENSOR_POINT3_SEARCH_RADIUS (4.f)
#define IMPROVE_BED_INDUCTION_SENSOR_POINT3_SEARCH_RADIUS (8.f)
#define IMPROVE_BED_INDUCTION_SENSOR_POINT3_SEARCH_STEP_FINE_Y (0.1f)
inline bool improve_bed_induction_sensor_point3(int verbosity_level)
{
@ -1873,6 +2135,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
if (!find_bed_induction_sensor_point_xy(verbosity_level))
return BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND;
#ifndef NEW_XYZCAL
#ifndef HEATBED_V2
if (k == 0 || k == 1) {
// Improve the position of the 1st row sensor points by a zig-zag movement.
@ -1893,6 +2156,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
// not found
return BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND;
}
#endif //HEATBED_V2
#endif
#ifdef SUPPORT_VERBOSITY
if (verbosity_level >= 10)
@ -2310,16 +2574,7 @@ BedSkewOffsetDetectionResultType improve_bed_offset_and_skew(int8_t method, int8
}
#endif // SUPPORT_VERBOSITY
//make space
current_position[Z_AXIS] += 150;
go_to_current(homing_feedrate[Z_AXIS] / 60);
//plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate, active_extruder););
lcd_show_fullscreen_message_and_wait_P(MSG_PLACE_STEEL_SHEET);
// Sample Z heights for the mesh bed leveling.
// In addition, store the results into an eeprom, to be used later for verification of the bed leveling process.
if (! sample_mesh_and_store_reference())
if(!sample_z())
goto canceled;
enable_endstops(endstops_enabled);
@ -2342,6 +2597,22 @@ canceled:
}
#endif //NEW_XYZCAL
bool sample_z() {
bool sampled = true;
//make space
current_position[Z_AXIS] += 150;
go_to_current(homing_feedrate[Z_AXIS] / 60);
//plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate, active_extruder););
lcd_show_fullscreen_message_and_wait_P(MSG_PLACE_STEEL_SHEET);
// Sample Z heights for the mesh bed leveling.
// In addition, store the results into an eeprom, to be used later for verification of the bed leveling process.
if (!sample_mesh_and_store_reference()) sampled = false;
return sampled;
}
void go_home_with_z_lift()
{
// Don't let the manage_inactivity() function remove power from the motors.
@ -2528,7 +2799,7 @@ bool scan_bed_induction_points(int8_t verbosity_level)
current_position[Y_AXIS] = Y_MIN_POS_FOR_BED_CALIBRATION;
go_to_current(homing_feedrate[X_AXIS]/60);
find_bed_induction_sensor_point_z();
scan_bed_induction_sensor_point();
scan_bed_induction_sensor_point();
}
// Don't let the manage_inactivity() function remove power from the motors.
refresh_cmd_timeout();
@ -2629,9 +2900,3 @@ void count_xyz_details() {
}
}
/*countDistanceFromMin() {
}*/

View File

@ -189,5 +189,6 @@ extern void babystep_undo();
// Reset the current babystep counter without moving the axes.
extern void babystep_reset();
extern void count_xyz_details();
extern bool sample_z();
#endif /* MESH_BED_CALIBRATION_H */

View File

@ -23,10 +23,6 @@
* Rambo Pin Assignments 1.3
******************************************************************/
#if MOTHERBOARD == 100 //100 - orig 301
#include "pins_Rambo.h"
#endif //MOTHERBOARD == 100
#if MOTHERBOARD == 200 //200 - orig 102
#include "pins_Rambo_1_0.h"
#endif //MOTHERBOARD == 200
@ -35,17 +31,9 @@
#include "pins_Rambo_1_3.h"
#endif //MOTHERBOARD == 203
#if MOTHERBOARD == 303 //303 - orig 300
#include "pins_Einy_0_3.h"
#endif //MOTHERBOARD == 303
#if MOTHERBOARD == 304 //304 - orig 299
#include "pins_Einy_0_4.h"
#endif //MOTHERBOARD == 304
#if MOTHERBOARD == 305 //305 - orig 298
#include "pins_Einy_0_4.h"
#endif //MOTHERBOARD == 305
#if MOTHERBOARD == 310 //310 - new
#include "pins_Einsy_1_0.h"
#endif //MOTHERBOARD == 310
#ifndef KNOWN_BOARD
#error Unknown MOTHERBOARD value in configuration.h

View File

@ -1,8 +1,8 @@
/*****************************************************************
* EINY Rambo 0.4a Pin Assignments
* EINSY Rambo 1.0a Pin Assignments
******************************************************************/
#define ELECTRONICS "EINY_04a"
#define ELECTRONICS "EINSy_10a"
#define KNOWN_BOARD
#ifndef __AVR_ATmega2560__
@ -10,7 +10,11 @@
#endif
#define TMC2130
#define PAT9125
#define UVLO_SUPPORT
#define AMBIENT_THERMISTOR
#define PINDA_THERMISTOR
#define SWI2C // enable software i2c
#define SWI2C_A8 // 8bit address functions
@ -85,9 +89,6 @@
#define E0_MS1_PIN -1
#define E0_MS2_PIN -1
#define MOTOR_CURRENT_PWM_XY_PIN 46
#define MOTOR_CURRENT_PWM_Z_PIN 45
#define MOTOR_CURRENT_PWM_E_PIN 44
#define SDPOWER -1
#define SDSS 77
#define LED_PIN 13

View File

@ -1,129 +0,0 @@
/*****************************************************************
* EINY Rambo 0.3a Pin Assignments
******************************************************************/
#define ELECTRONICS "EINY_03a"
#define KNOWN_BOARD
#ifndef __AVR_ATmega2560__
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
#endif
#define TMC2130
#define PAT9125
#define SWI2C // enable software i2c
#define SWI2C_A8 // 8bit address functions
#define PAT9125_SWI2C
#define PAT9125_SWI2C_SDA 20 //SDA on P3
#define PAT9125_SWI2C_SCL 21 //SCL on P3
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
//#define SWSPI_MISO 16 //RX2
//#define SWSPI_MOSI 16 //RX2
//#define SWSPI_SCK 17 //TX2
//#define SWSPI_CS 20 //SDA
////#define SWI2C_SDA 20 //SDA
////#define SWI2C_SCL 21 //SCL
//#define SWI2C_SDA 16 //RX2
//#define SWI2C_SCL 17 //TX2
#define X_TMC2130_CS 41
#define X_TMC2130_DIAG 40
#define X_STEP_PIN 37
#define X_DIR_PIN 49
//#define X_MIN_PIN 12
//#define X_MAX_PIN 30
#define X_MIN_PIN X_TMC2130_DIAG
#define X_MAX_PIN X_TMC2130_DIAG
#define X_ENABLE_PIN 29
#define X_MS1_PIN -1
#define X_MS2_PIN -1
#define Y_TMC2130_CS 39
#define Y_TMC2130_DIAG 69
#define Y_STEP_PIN 36
#define Y_DIR_PIN 48
//#define Y_MIN_PIN 11
//#define Y_MAX_PIN 24
#define Y_MIN_PIN Y_TMC2130_DIAG
#define Y_MAX_PIN Y_TMC2130_DIAG
#define Y_ENABLE_PIN 28
#define Y_MS1_PIN -1
#define Y_MS2_PIN -1
#define Z_TMC2130_CS 67
#define Z_TMC2130_DIAG 68
#define Z_STEP_PIN 35
#define Z_DIR_PIN 47
#define Z_MIN_PIN 10
#define Z_MAX_PIN 23
//#define Z_MAX_PIN Z_TMC2130_DIAG
#define Z_ENABLE_PIN 27
#define Z_MS1_PIN -1
#define Z_MS2_PIN -1
#define HEATER_BED_PIN 4 //PG5
#define TEMP_BED_PIN 2 //A2
#define HEATER_0_PIN 3 //PE5
#define TEMP_0_PIN 0 //A0
#define HEATER_1_PIN -1
#define TEMP_1_PIN 1 //A1
#define HEATER_2_PIN -1
#define TEMP_2_PIN -1
#define TEMP_AMBIENT_PIN 6 //A6
#define TEMP_PINDA_PIN 3 //A3
#define E0_TMC2130_CS 66
#define E0_TMC2130_DIAG 65
#define E0_STEP_PIN 34
#define E0_DIR_PIN 43
#define E0_ENABLE_PIN 26
#define E0_MS1_PIN -1
#define E0_MS2_PIN -1
#define MOTOR_CURRENT_PWM_XY_PIN 46
#define MOTOR_CURRENT_PWM_Z_PIN 45
#define MOTOR_CURRENT_PWM_E_PIN 44
#define SDPOWER -1
#define SDSS 53
#define LED_PIN 13
#define FAN_PIN 6
#define FAN_1_PIN -1
#define PS_ON_PIN -1
#define KILL_PIN -1 // 80 with Smart Controller LCD
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
#ifdef ULTRA_LCD
//#define KILL_PIN 32
#ifdef NEWPANEL
#define BEEPER 84 // Beeper on AUX-4
#define LCD_PINS_RS 82
#define LCD_PINS_ENABLE 18
#define LCD_PINS_D4 19
#define LCD_PINS_D5 70
#define LCD_PINS_D6 85
#define LCD_PINS_D7 71
//buttons are directly attached using AUX-2
#define BTN_EN1 72
#define BTN_EN2 14
#define BTN_ENC 9 // the click
#define SDCARDDETECT 15
#define TACH_0 81
#define TACH_1 80
#endif //NEWPANEL
#endif //ULTRA_LCD

View File

@ -1,162 +0,0 @@
/*****************************************************************
* Rambo Pin Assignments
******************************************************************/
#define ELECTRONICS "RAMBoBig"
#define KNOWN_BOARD
#ifndef __AVR_ATmega2560__
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
#endif
#define FR_SENS 21
#define X_STEP_PIN 37
#define X_DIR_PIN 48
#define X_MIN_PIN 12
#define X_MAX_PIN 30
#define X_ENABLE_PIN 29
#define X_MS1_PIN 40
#define X_MS2_PIN 41
#define Y_STEP_PIN 36
#define Y_DIR_PIN 49
#define Y_MIN_PIN 11
#define Y_MAX_PIN 24
#define Y_ENABLE_PIN 28
#define Y_MS1_PIN 69
#define Y_MS2_PIN 39
#define Z_STEP_PIN 35
#define Z_DIR_PIN 47
#define Z_MIN_PIN 10
#define Z_MAX_PIN 23
#define Z_ENABLE_PIN 27
#define Z_MS1_PIN 68
#define Z_MS2_PIN 67
#define TEMP_BED_PIN 2
#define TEMP_0_PIN 0
#define HEATER_1_PIN 7
#define TEMP_1_PIN 1
#define TEMP_2_PIN -1
#ifdef SNMM
#define E_MUX0_PIN 17
#define E_MUX1_PIN 16
#define E_MUX2_PIN 84
#endif
#ifdef DIS
#define D_REQUIRE 30
#define D_DATA 20
#define D_DATACLOCK 21
#endif
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
#define SDSS 53
#ifndef SDSUPPORT
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 52
#define MISO_PIN 50
#define MOSI_PIN 51
#endif
#define BEEPER 84
#define BTN_EN1 72
#define BTN_EN2 14
#define BTN_ENC 9
#define SDCARDDETECT 15
#define LCD_PINS_RS 82
#define LCD_PINS_ENABLE 18
#define LCD_PINS_D4 19
#define LCD_PINS_D5 70
#define LCD_PINS_D6 85
#define LCD_PINS_D7 71
#define E0_STEP_PIN 34
#define E0_DIR_PIN 43
#define E0_ENABLE_PIN 26
#define E0_MS1_PIN 65
#define E0_MS2_PIN 66
#define LED_PIN 13
#ifdef THREEMM_PRINTER
#define FAN_PIN 8
#else
#define FAN_PIN 6
#endif
#define KILL_PIN -1 //80 with Smart Controller LCD
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
#define SDPOWER -1
#define HEATER_2_PIN -1
#define E1_STEP_PIN 33
#define E1_DIR_PIN 42
#define E1_ENABLE_PIN 25
#define E1_MS1_PIN 63
#define E1_MS2_PIN 64
#define DIGIPOTSS_PIN 38
#define DIGIPOT_CHANNELS {4,5,3,0,1} // X Y Z E0 E1 digipot channels to stepper driver mapping
#define HEATER_0_PIN 9
#define HEATER_BED_PIN 3
#define PS_ON_PIN 4
#define SDSS 53
#ifdef ULTRA_LCD
#define KILL_PIN 80
#ifdef NEWPANEL
//arduino pin which triggers an piezzo beeper
#define BEEPER 84 // Beeper on AUX-4
#define LCD_PINS_RS 82
#define LCD_PINS_ENABLE 18
#define LCD_PINS_D4 19
#define LCD_PINS_D5 70
#define LCD_PINS_D6 85
#define LCD_PINS_D7 71
//buttons are directly attached using AUX-2
#define BTN_EN1 76
#define BTN_EN2 77
#define BTN_ENC 78 //the click
#define BLEN_C 2
#define BLEN_B 1
#define BLEN_A 0
#define SDCARDDETECT 81 // Ramps does not use this port
//encoder rotation values
#define encrot0 0
#define encrot1 2
#define encrot2 3
#define encrot3 1
#else //old style panel with shift register
//arduino pin witch triggers an piezzo beeper
#define BEEPER 84 //No Beeper added
//buttons are attached to a shift register
// Not wired this yet
// #define SHIFT_CLK 38
// #define SHIFT_LD 42
// #define SHIFT_OUT 40
// #define SHIFT_EN 17
#define LCD_PINS_RS 82
#define LCD_PINS_ENABLE 18
#define LCD_PINS_D4 19
#define LCD_PINS_D5 70
#define LCD_PINS_D6 85
#define LCD_PINS_D7 71
//encoder rotation values
#define encrot0 0
#define encrot1 2
#define encrot2 3
#define encrot3 1
//bits in the shift register that carry the buttons for:
// left up center down right red
#define BL_LE 7
#define BL_UP 6
#define BL_MI 5
#define BL_DW 4
#define BL_RI 3
#define BL_ST 2
#define BLEN_B 1
#define BLEN_A 0
#endif
#endif //ULTRA_LCD

View File

@ -1,94 +0,0 @@
/*****************************************************************
* Rambo mini 1.0 Pin Assignments
******************************************************************/
#define ELECTRONICS "RAMBo10a"
#define KNOWN_BOARD
#ifndef __AVR_ATmega2560__
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
#endif
#define FR_SENS 21
#define X_STEP_PIN 37
#define X_DIR_PIN 48
#define X_MIN_PIN 12
#define X_MAX_PIN 30
#define X_ENABLE_PIN 29
#define X_MS1_PIN 40
#define X_MS2_PIN 41
#define Y_STEP_PIN 36
#define Y_DIR_PIN 49
#define Y_MIN_PIN 11
#define Y_MAX_PIN 24
#define Y_ENABLE_PIN 28
#define Y_MS1_PIN 69
#define Y_MS2_PIN 39
#define Z_STEP_PIN 35
#define Z_DIR_PIN 47
#define Z_MIN_PIN 10
#define Z_MAX_PIN 23
#define Z_ENABLE_PIN 27
#define Z_MS1_PIN 68
#define Z_MS2_PIN 67
#define TEMP_BED_PIN 2
#define TEMP_0_PIN 0
#define HEATER_1_PIN 7
#define TEMP_1_PIN 1
#define TEMP_2_PIN -1
#ifdef SNMM
#define E_MUX0_PIN 17
#define E_MUX1_PIN 16
#define E_MUX2_PIN 84
#endif
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
#define SDSS 53
#ifndef SDSUPPORT
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 52
#define MISO_PIN 50
#define MOSI_PIN 51
#endif
#define BEEPER 78
#define BTN_EN1 80
#define BTN_EN2 73
#define BTN_ENC 21
#define SDCARDDETECT 72
#define LCD_PINS_RS 38
#define LCD_PINS_ENABLE 5
#define LCD_PINS_D4 14
#define LCD_PINS_D5 15
#define LCD_PINS_D6 32
#define LCD_PINS_D7 31
#define E0_STEP_PIN 34
#define E0_DIR_PIN 43
#define E0_ENABLE_PIN 26
#define E0_MS1_PIN 65
#define E0_MS2_PIN 66
#define LED_PIN 13
#ifdef THREEMM_PRINTER
#define FAN_PIN 8
#else
#define FAN_PIN 6
#endif
#define KILL_PIN -1 //80 with Smart Controller LCD
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
#define SDPOWER -1
#define HEATER_2_PIN -1
#define HEATER_0_PIN 3
#define HEATER_BED_PIN 4
#define FAN_1_PIN -1 //6
#define PS_ON_PIN 71
#define MOTOR_CURRENT_PWM_XY_PIN 46
#define MOTOR_CURRENT_PWM_Z_PIN 45
#define MOTOR_CURRENT_PWM_E_PIN 44

View File

@ -6,25 +6,37 @@
#define KNOWN_BOARD
#ifndef __AVR_ATmega2560__
#error Oops! Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu.
#error Oops! Make sure you have 'Arduino Mega 2560 or Rambo' selected from the 'Tools -> Boards' menu.
#endif
#define FR_SENS 21
#define PINDA_THERMISTOR
#define SWI2C // enable software i2c
#define SWI2C_A8 // 8bit address functions
#define PAT9125_SWI2C
#define PAT9125_SWI2C_SDA 20 //SDA on P3
#define PAT9125_SWI2C_SCL 21 //SCL on P3
#define PAT9125_SWI2C_CFG 0xb1 //2us clock delay, 2048 cycles timeout
//#define PAT9125_HWI2C
#define X_STEP_PIN 37
#define X_DIR_PIN 48
#define X_MIN_PIN 12
#define X_MAX_PIN 30
#define X_MAX_PIN -1
#define X_ENABLE_PIN 29
#define X_MS1_PIN 40
#define X_MS2_PIN 41
#define Y_STEP_PIN 36
#define Y_DIR_PIN 49
#define Y_MIN_PIN 11
#define Y_MAX_PIN 24
#define Y_MAX_PIN -1
#define Y_ENABLE_PIN 28
#define Y_MS1_PIN 69
#define Y_MS2_PIN 39
#define Z_STEP_PIN 35
#define Z_DIR_PIN 47
#define Z_MIN_PIN 10
@ -32,71 +44,91 @@
#define Z_ENABLE_PIN 27
#define Z_MS1_PIN 68
#define Z_MS2_PIN 67
#define TEMP_BED_PIN 2
#define TEMP_0_PIN 0
#define HEATER_1_PIN 7
#define TEMP_1_PIN 1
#define HEATER_BED_PIN 4 //PG5
#define TEMP_BED_PIN 2 //A2
#define HEATER_0_PIN 3 //PE5
#define TEMP_0_PIN 0 //A0
#define HEATER_1_PIN -1
#define TEMP_1_PIN -1 //A1
#define HEATER_2_PIN -1
#define TEMP_2_PIN -1
#ifdef SNMM
#define E_MUX0_PIN 17
#define E_MUX1_PIN 16
#define E_MUX2_PIN 84
#endif
#define TEMP_AMBIENT_PIN 6 //A6
#ifdef DIS
#define D_REQUIRE 30
#define D_DATA 20
#define D_DATACLOCK 21
#endif
#define TEMP_PINDA_PIN 1 //A1
// The SDSS pin uses a different pin mapping from file Sd2PinMap.h
#define SDSS 53
#ifndef SDSUPPORT
// these pins are defined in the SD library if building with SD support
#define SCK_PIN 52
#define MISO_PIN 50
#define MOSI_PIN 51
#endif
#define BEEPER 84
#define BTN_EN1 72
#define BTN_EN2 14
#define BTN_ENC 9
#define SDCARDDETECT 15
#define LCD_PINS_RS 82
#define LCD_PINS_ENABLE 18
#define LCD_PINS_D4 19
#define LCD_PINS_D5 70
#define LCD_PINS_D6 85
#define LCD_PINS_D7 71
#define E0_STEP_PIN 34
#define E0_DIR_PIN 43
#define E0_ENABLE_PIN 26
#define E0_MS1_PIN 65
#define E0_MS2_PIN 66
#define LED_PIN 13
#ifdef THREEMM_PRINTER
#define FAN_PIN 8
#else
#define FAN_PIN 6
#endif
#define KILL_PIN -1 //80 with Smart Controller LCD
#define SUICIDE_PIN -1 //PIN that has to be turned on right after start, to keep power flowing.
#define SDPOWER -1
#define HEATER_2_PIN -1
#define MOTOR_CURRENT_PWM_XY_PIN 46
#define MOTOR_CURRENT_PWM_Z_PIN 45
#define MOTOR_CURRENT_PWM_E_PIN 44
#define SDPOWER -1
#define SDSS 53
#define LED_PIN 13
#define FAN_PIN 6
#define FAN_1_PIN -1
#define PS_ON_PIN -1
#define KILL_PIN -1 // 80 with Smart Controller LCD
#define SUICIDE_PIN -1 // PIN that has to be turned on right after start, to keep power flowing.
#define TACH_0 30 // noctua extruder fan
#ifdef ULTRA_LCD
//#define KILL_PIN 32
#ifdef NEWPANEL
#define BEEPER 84 // Beeper on AUX-4
#define LCD_PINS_RS 82
#define LCD_PINS_ENABLE 18
#define LCD_PINS_D4 19
#define LCD_PINS_D5 70
#define LCD_PINS_D6 85
#define LCD_PINS_D7 71
//buttons are directly attached using AUX-2
#define BTN_EN1 72
#define BTN_EN2 14
#define BTN_ENC 9 // the click
#define SDCARDDETECT 15
#endif //NEWPANEL
#endif //ULTRA_LCD
// Support for an 8 bit logic analyzer, for example the Saleae.
// Channels 0-2 are fast, they could generate 2.667Mhz waveform with a software loop.
#define LOGIC_ANALYZER_CH0 X_MIN_PIN // PB6
#define LOGIC_ANALYZER_CH1 Y_MIN_PIN // PB5
#define LOGIC_ANALYZER_CH2 53 // PB0 (PROC_nCS)
// Channels 3-7 are slow, they could generate
// 0.889Mhz waveform with a software loop and interrupt locking,
// 1.333MHz waveform without interrupt locking.
#define LOGIC_ANALYZER_CH3 73 // PJ3
// PK0 has no Arduino digital pin assigned, so we set it directly.
#define WRITE_LOGIC_ANALYZER_CH4(value) if (value) PORTK |= (1 << 0); else PORTK &= ~(1 << 0) // PK0
#define LOGIC_ANALYZER_CH5 16 // PH0 (RXD2)
#define LOGIC_ANALYZER_CH6 17 // PH1 (TXD2)
#define LOGIC_ANALYZER_CH7 76 // PJ5
#define LOGIC_ANALYZER_CH0_ENABLE SET_OUTPUT(LOGIC_ANALYZER_CH0)
#define LOGIC_ANALYZER_CH1_ENABLE SET_OUTPUT(LOGIC_ANALYZER_CH1)
#define LOGIC_ANALYZER_CH2_ENABLE SET_OUTPUT(LOGIC_ANALYZER_CH2)
#define LOGIC_ANALYZER_CH3_ENABLE SET_OUTPUT(LOGIC_ANALYZER_CH3)
#define LOGIC_ANALYZER_CH4_ENABLE do { DDRK |= 1 << 0; } while (0)
#define LOGIC_ANALYZER_CH5_ENABLE do { cbi(UCSR2B, TXEN2); cbi(UCSR2B, RXEN2); cbi(UCSR2B, RXCIE2); SET_OUTPUT(LOGIC_ANALYZER_CH5); } while (0)
#define LOGIC_ANALYZER_CH6_ENABLE do { cbi(UCSR2B, TXEN2); cbi(UCSR2B, RXEN2); cbi(UCSR2B, RXCIE2); SET_OUTPUT(LOGIC_ANALYZER_CH6); } while (0)
#define LOGIC_ANALYZER_CH7_ENABLE SET_OUTPUT(LOGIC_ANALYZER_CH7)
#define HEATER_0_PIN 3
#define HEATER_BED_PIN 4
#define FAN_1_PIN -1 //6
#define PS_ON_PIN 71
#define MOTOR_CURRENT_PWM_XY_PIN 46
#define MOTOR_CURRENT_PWM_Z_PIN 45
#define MOTOR_CURRENT_PWM_E_PIN 44

14
Firmware/printers.h Normal file
View File

@ -0,0 +1,14 @@
#ifndef PRINTERS_H
#define PRINTERS_H
#define PRINTER_UNKNOWN 0
#define PRINTER_MK1 100
#define PRINTER_MK2 200
#define PRINTER_MK2_SNMM 201
#define PRINTER_MK25 250
#define PRINTER_MK25_SNMM 251
#define PRINTER_MK3 300
#define PRINTER_MK3_SNMM 301
#endif //PRINTERS_H

View File

@ -53,7 +53,7 @@ uint8_t sm4_get_dir(uint8_t axis)
case 1: return (PORTL & 1)?0:1;
case 2: return (PORTL & 4)?0:1;
case 3: return (PORTL & 64)?1:0;
#else if ((MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#else if ((MOTHERBOARD == 310))
case 0: return (PORTL & 1)?1:0;
case 1: return (PORTL & 2)?0:1;
case 2: return (PORTL & 4)?1:0;
@ -72,7 +72,7 @@ void sm4_set_dir(uint8_t axis, uint8_t dir)
case 1: if (!dir) PORTL |= 1; else PORTL &= ~1; break;
case 2: if (!dir) PORTL |= 4; else PORTL &= ~4; break;
case 3: if (dir) PORTL |= 64; else PORTL &= ~64; break;
#else if ((MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#else if ((MOTHERBOARD == 310))
case 0: if (dir) PORTL |= 1; else PORTL &= ~1; break;
case 1: if (!dir) PORTL |= 2; else PORTL &= ~2; break;
case 2: if (dir) PORTL |= 4; else PORTL &= ~4; break;
@ -93,7 +93,7 @@ uint8_t sm4_get_dir_bits(void)
if (portL & 4) dir_bits |= 4;
if (portL & 64) dir_bits |= 8;
dir_bits ^= 0x07; //invert XYZ, do not invert E
#else if ((MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#else if ((MOTHERBOARD == 310))
if (portL & 1) dir_bits |= 1;
if (portL & 2) dir_bits |= 2;
if (portL & 4) dir_bits |= 4;
@ -114,7 +114,7 @@ void sm4_set_dir_bits(uint8_t dir_bits)
if (dir_bits & 2) portL |= 1; //set Y direction bit
if (dir_bits & 4) portL |= 4; //set Z direction bit
if (dir_bits & 8) portL |= 64; //set E direction bit
#else if ((MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#else if ((MOTHERBOARD == 310))
dir_bits ^= 0x0a; //invert YE, do not invert XZ
if (dir_bits & 1) portL |= 1; //set X direction bit
if (dir_bits & 2) portL |= 2; //set Y direction bit
@ -127,13 +127,13 @@ void sm4_set_dir_bits(uint8_t dir_bits)
void sm4_do_step(uint8_t axes_mask)
{
#if ((MOTHERBOARD == 200) || (MOTHERBOARD == 203) || (MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#if ((MOTHERBOARD == 200) || (MOTHERBOARD == 203) || (MOTHERBOARD == 310))
uint8_t register portC = PORTC & 0xf0;
PORTC = portC | (axes_mask & 0x0f); //set step signals by mask
asm("nop");
PORTC = portC; //set step signals to zero
asm("nop");
#endif //((MOTHERBOARD == 200) || (MOTHERBOARD == 203) || (MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#endif //((MOTHERBOARD == 200) || (MOTHERBOARD == 203) || (MOTHERBOARD == 310))
}
uint16_t sm4_line_xyze_ui(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de)

View File

@ -99,6 +99,7 @@ static bool old_z_max_endstop=false;
static bool check_endstops = true;
static bool check_z_endstop = false;
static bool z_endstop_invert = false;
int8_t SilentMode = 0;
@ -284,10 +285,15 @@ bool enable_endstops(bool check)
bool enable_z_endstop(bool check)
{
bool old = check_z_endstop;
check_z_endstop = check;
endstop_z_hit=false;
return old;
bool old = check_z_endstop;
check_z_endstop = check;
endstop_z_hit = false;
return old;
}
void invert_z_endstop(bool endstop_invert)
{
z_endstop_invert = endstop_invert;
}
// __________________________
@ -630,6 +636,7 @@ FORCE_INLINE void stepper_check_endstops()
#endif
}
FORCE_INLINE void stepper_tick_lowres()
{
for (uint8_t i=0; i < step_loops; ++ i) { // Take multiple steps per interrupt (For high speed moves)
@ -1144,6 +1151,13 @@ void st_init()
#endif
#endif
#if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 > -1))
SET_INPUT(TACH_0);
#ifdef TACH0PULLUP
WRITE(TACH_0, HIGH);
#endif
#endif
//Initialize Step Pins
#if defined(X_STEP_PIN) && (X_STEP_PIN > -1)
@ -1442,10 +1456,9 @@ void EEPROM_read_st(int pos, uint8_t* value, uint8_t size)
void digipot_init() //Initialize Digipot Motor Current
{
{
EEPROM_read_st(EEPROM_SILENT,(uint8_t*)&SilentMode,sizeof(SilentMode));
SilentModeMenu = SilentMode;
#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
if(SilentMode == 0){
const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT_LOUD;

View File

@ -79,6 +79,7 @@ bool endstop_z_hit_on_purpose();
bool enable_endstops(bool check); // Enable/disable endstop checking. Return the old value.
bool enable_z_endstop(bool check);
void invert_z_endstop(bool endstop_invert);
void checkStepperErrors(); //Print errors detected by the stepper

View File

@ -32,7 +32,6 @@
#include "Marlin.h"
#include "ultralcd.h"
#include "temperature.h"
#include "watchdog.h"
#include "cardreader.h"
#include "Sd2PinMap.h"
@ -262,7 +261,9 @@ unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
for(;;) {
wdt_reset();
#ifdef WATCHDOG
wdt_reset();
#endif //WATCHDOG
if(temp_meas_ready == true) { // temp sample ready
updateTemperaturesFromRawValues();
@ -448,6 +449,8 @@ void setExtruderAutoFanState(int pin, bool state)
analogWrite(pin, newFanSpeed);
}
#if (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))
void countFanSpeed()
{
//SERIAL_ECHOPGM("edge counter 1:"); MYSERIAL.println(fan_edge_counter[1]);
@ -467,12 +470,14 @@ void checkFanSpeed()
{
fans_check_enabled = (eeprom_read_byte((uint8_t*)EEPROM_FAN_CHECK_ENABLED) > 0);
static unsigned char fan_speed_errors[2] = { 0,0 };
if ((fan_speed[0] == 0) && (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)) fan_speed_errors[0]++;
#if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 >-1))
if (fan_speed[0] == 0 && (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)) fan_speed_errors[0]++;
else fan_speed_errors[0] = 0;
if ((fan_speed[1] == 0) && ((blocks_queued()?block_buffer[block_buffer_tail].fan_speed:fanSpeed) > MIN_PRINT_FAN_SPEED)) fan_speed_errors[1]++;
#endif
#if (defined(FANCHECK) && defined(TACH_1) && (TACH_1 >-1))
if ((fan_speed[1] == 0)&& (fanSpeed > MIN_PRINT_FAN_SPEED)) fan_speed_errors[1]++;
else fan_speed_errors[1] = 0;
#endif
if ((fan_speed_errors[0] > 5) && fans_check_enabled) {
fan_speed_errors[0] = 0;
@ -526,6 +531,7 @@ void fanSpeedError(unsigned char _fan) {
break;
}
}
#endif //(defined(TACH_0) && TACH_0 >-1) || (defined(TACH_1) && TACH_1 > -1)
void checkExtruderAutoFans()
@ -577,7 +583,9 @@ void checkExtruderAutoFans()
void manage_heater()
{
wdt_reset();
#ifdef WATCHDOG
wdt_reset();
#endif //WATCHDOG
float pid_input;
float pid_output;
@ -660,11 +668,16 @@ void manage_heater()
#endif
// Check if temperature is within the correct range
#ifdef AMBIENT_THERMISTOR
if(((current_temperature_ambient < MINTEMP_MINAMBIENT) || (current_temperature[e] > minttemp[e])) && (current_temperature[e] < maxttemp[e]))
#else //AMBIENT_THERMISTOR
if((current_temperature[e] > minttemp[e]) && (current_temperature[e] < maxttemp[e]))
#endif //AMBIENT_THERMISTOR
{
soft_pwm[e] = (int)pid_output >> 1;
}
else {
else
{
soft_pwm[e] = 0;
}
@ -703,8 +716,10 @@ void manage_heater()
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
if(millis() - extruder_autofan_last_check > 1000) // only need to check fan state very infrequently
{
#if (defined(FANCHECK) && ((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1))))
countFanSpeed();
checkFanSpeed();
#endif //(defined(TACH_0) && TACH_0 >-1) || (defined(TACH_1) && TACH_1 > -1)
checkExtruderAutoFans();
extruder_autofan_last_check = millis();
}
@ -747,7 +762,11 @@ void manage_heater()
pid_output = constrain(target_temperature_bed, 0, MAX_BED_POWER);
#endif //PID_OPENLOOP
#ifdef AMBIENT_THERMISTOR
if(((current_temperature_bed > BED_MINTEMP) || (current_temperature_ambient < MINTEMP_MINAMBIENT)) && (current_temperature_bed < BED_MAXTEMP))
#else //AMBIENT_THERMISTOR
if((current_temperature_bed > BED_MINTEMP) && (current_temperature_bed < BED_MAXTEMP))
#endif //AMBIENT_THERMISTOR
{
soft_pwm_bed = (int)pid_output >> 1;
}
@ -903,6 +922,7 @@ static float analog2tempBed(int raw) {
#endif
}
#ifdef AMBIENT_THERMISTOR
static float analog2tempAmbient(int raw)
{
float celsius = 0;
@ -923,6 +943,7 @@ static float analog2tempAmbient(int raw)
if (i == AMBIENTTEMPTABLE_LEN) celsius = PGM_RD_W(AMBIENTTEMPTABLE[i-1][1]);
return celsius;
}
#endif //AMBIENT_THERMISTOR
/* Called to get the raw values into the the actual temperatures. The raw values are created in interrupt context,
and this function is called from normal context as it is too slow to run in interrupts and will block the stepper routine otherwise */
@ -948,7 +969,9 @@ static void updateTemperaturesFromRawValues()
#endif
//Reset the watchdog after we know we have a temperature measurement.
watchdog_reset();
#ifdef WATCHDOG
wdt_reset();
#endif //WATCHDOG
CRITICAL_SECTION_START;
temp_meas_ready = false;
@ -1482,11 +1505,17 @@ extern "C" {
void adc_ready(void) //callback from adc when sampling finished
{
current_temperature_raw[0] = adc_values[0];
current_temperature_bed_raw = adc_values[2];
current_temperature_raw_pinda = adc_values[3];
current_temperature_raw_pinda = adc_values[1];
current_temperature_bed_raw = adc_values[2];
#ifdef VOLT_PWR_PIN
current_voltage_raw_pwr = adc_values[4];
#endif
#ifdef AMBIENT_THERMISTOR
current_temperature_raw_ambient = adc_values[5];
#endif //AMBIENT_THERMISTOR
#ifdef VOLT_BED_PIN
current_voltage_raw_bed = adc_values[6];
#endif
temp_meas_ready = true;
}
@ -1843,7 +1872,9 @@ ISR(TIMER0_COMPB_vect)
}
#endif //BABYSTEPPING
#if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 > -1))
check_fans();
#endif //(defined(TACH_0))
_lock = false;
}
@ -1897,6 +1928,7 @@ void check_min_temp_bed()
void check_min_temp()
{
#ifdef AMBIENT_THERMISTOR
static uint8_t heat_cycles = 0;
if (current_temperature_raw_ambient > OVERSAMPLENR*MINTEMP_MINAMBIENT_RAW)
{
@ -1913,10 +1945,12 @@ void check_min_temp()
heat_cycles = 0;
return;
}
#endif //AMBIENT_THERMISTOR
check_min_temp_heater0();
check_min_temp_bed();
}
#if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 > -1))
void check_fans() {
if (READ(TACH_0) != fan_state[0]) {
fan_edge_counter[0] ++;
@ -1927,6 +1961,7 @@ void check_fans() {
// fan_state[1] = !fan_state[1];
//}
}
#endif //TACH_0
#ifdef PIDTEMP
// Apply the scale factors to the PID values

View File

@ -221,13 +221,20 @@ void PID_autotune(float temp, int extruder, int ncycles);
void setExtruderAutoFanState(int pin, bool state);
void checkExtruderAutoFans();
#if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 > -1))
void countFanSpeed();
void checkFanSpeed();
void fanSpeedError(unsigned char _fan);
void check_fans();
#endif //(defined(TACH_0))
void check_min_temp();
void check_max_temp();
#endif

File diff suppressed because it is too large Load Diff

View File

@ -41,16 +41,21 @@ void lcd_mylang();
#ifdef TMC2130
static void reset_crash_det(char axis);
static bool lcd_selfcheck_axis_sg(char axis);
#endif //TMC2130
static bool lcd_selfcheck_axis(int _axis, int _travel);
#else
static bool lcd_selfcheck_endstops();
static bool lcd_selfcheck_axis(int _axis, int _travel);
static bool lcd_selfcheck_pulleys(int axis);
#endif //TMC2130
static bool lcd_selfcheck_check_heater(bool _isbed);
static int lcd_selftest_screen(int _step, int _progress, int _progress_scale, bool _clear, int _delay);
static void lcd_selftest_screen_step(int _row, int _col, int _state, const char *_name, const char *_indicator);
static bool lcd_selftest_manual_fan_check(int _fan, bool check_opposite);
static bool lcd_selftest_fan_dialog(int _fan);
static bool lcd_selftest_fsensor();
static void lcd_selftest_error(int _error_no, const char *_error_1, const char *_error_2);
void lcd_menu_statistics();
static bool lcd_selfcheck_pulleys(int axis);
void lcd_menu_statistics();
extern const char* lcd_display_message_fullscreen_P(const char *msg, uint8_t &nlines);
inline const char* lcd_display_message_fullscreen_P(const char *msg)
@ -114,6 +119,7 @@ void lcd_mylang();
extern int farm_no;
extern int farm_timer;
extern int farm_status;
extern int8_t SilentModeMenu;
#ifdef SNMM
extern uint8_t snmm_extruder;

View File

@ -1,245 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "1_75mm"
#define NOZZLE_TYPE "E3Dv6full"
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3"
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_0
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/0.8,161.3}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 0.25
// Travel limits after homing
#define X_MAX_POS 214
#define X_MIN_POS 0
#define Y_MAX_POS 198
#define Y_MIN_POS 0
#define Z_MAX_POS 201
#define Z_MIN_POS 0.23
// Canceled home position
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 180
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
#define DEFAULT_MAX_FEEDRATE {500, 500, 3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 240, 60} // set the speeds for manual moves (mm/min)
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 15
// Maxtemps
#define HEATER_0_MAXTEMP 310
#define HEATER_1_MAXTEMP 310
#define HEATER_2_MAXTEMP 310
#define BED_MAXTEMP 150
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E70 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 70
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 300
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 450, 450} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 450, 500} // {XY,Z,E}
#endif
/*------------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 210
#define PLA_PREHEAT_HPB_TEMP 50
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 0
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_BED 1
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,244 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "1_75mm"
#define NOZZLE_TYPE "E3Dv6lite"
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3"
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_0
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/0.8,161.3}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 0.25
// Travel limits after homing
#define X_MAX_POS 214
#define X_MIN_POS 0
#define Y_MAX_POS 198
#define Y_MIN_POS 0
#define Z_MAX_POS 201
#define Z_MIN_POS 0.23
// Canceled home position
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 180
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
#define DEFAULT_MAX_FEEDRATE {500, 500, 3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 240, 60} // set the speeds for manual moves (mm/min)
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 15
// Maxtemps
#define HEATER_0_MAXTEMP 265
#define HEATER_1_MAXTEMP 265
#define HEATER_2_MAXTEMP 265
#define BED_MAXTEMP 150
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E70 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 70
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 300
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 450, 450} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 450, 500} // {XY,Z,E}
#endif
/*------------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 210
#define PLA_PREHEAT_HPB_TEMP 50
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 0
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_BED 1
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,244 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "1_75mm"
#define NOZZLE_TYPE "E3Dv6full"
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3"
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_3
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/0.8,161.3}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 0.25
// Travel limits after homing
#define X_MAX_POS 214
#define X_MIN_POS 0
#define Y_MAX_POS 198
#define Y_MIN_POS 0
#define Z_MAX_POS 201
#define Z_MIN_POS 0.23
// Canceled home position
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 180
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
#define DEFAULT_MAX_FEEDRATE {500, 500, 3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 240, 60} // set the speeds for manual moves (mm/min)
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 15
// Maxtemps
#define HEATER_0_MAXTEMP 310
#define HEATER_1_MAXTEMP 310
#define HEATER_2_MAXTEMP 310
#define BED_MAXTEMP 150
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E70 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 70
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 300
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 450, 450} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 450, 500} // {XY,Z,E}
#endif
/*------------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 210
#define PLA_PREHEAT_HPB_TEMP 50
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 0
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_BED 1
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,244 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "1_75mm"
#define NOZZLE_TYPE "E3Dv6lite"
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3"
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_3
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/0.8,161.3}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 0.25
// Travel limits after homing
#define X_MAX_POS 214
#define X_MIN_POS 0
#define Y_MAX_POS 198
#define Y_MIN_POS 0
#define Z_MAX_POS 201
#define Z_MIN_POS 0.23
// Canceled home position
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 180
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
#define DEFAULT_MAX_FEEDRATE {500, 500, 3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 240, 60} // set the speeds for manual moves (mm/min)
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 15
// Maxtemps
#define HEATER_0_MAXTEMP 265
#define HEATER_1_MAXTEMP 265
#define HEATER_2_MAXTEMP 265
#define BED_MAXTEMP 150
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E70 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 70
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 300
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 450, 450} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 450, 500} // {XY,Z,E}
#endif
/*------------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 210
#define PLA_PREHEAT_HPB_TEMP 50
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 0
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_BED 1
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,316 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "1_75mm_MK2"
#define NOZZLE_TYPE "E3Dv6full"
// Developer flag
#define DEVELOPER
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3 MK2"
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_0
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,161.3}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS -2.2
#define MANUAL_Z_HOME_POS 0.2
// Travel limits after homing
#define X_MAX_POS 255
#define X_MIN_POS 0
#define Y_MAX_POS 210
#define Y_MIN_POS -4
#define Z_MAX_POS 210
#define Z_MIN_POS 0.2
// Canceled home position
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 190
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min)
#define DEFAULT_MAX_FEEDRATE {500, 500, 1000, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,1000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 1000, 100} // set the speeds for manual moves (mm/min)
#define Z_AXIS_ALWAYS_ON 1
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 15
// Maxtemps
#define HEATER_0_MAXTEMP 305
#define HEATER_1_MAXTEMP 305
#define HEATER_2_MAXTEMP 305
#define BED_MAXTEMP 150
// Define PID constants for extruder
#define DEFAULT_Kp 40.925
#define DEFAULT_Ki 4.875
#define DEFAULT_Kd 86.085
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E70 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 50
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 15
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 830, 450} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 830, 500} // {XY,Z,E}
#endif
/*------------------------------------
BED SETTINGS
*------------------------------------*/
// Define Mesh Bed Leveling system to enable it
#define MESH_BED_LEVELING
#ifdef MESH_BED_LEVELING
#define MBL_Z_STEP 0.01
// Mesh definitions
#define MESH_MIN_X 35
#define MESH_MAX_X 238
#define MESH_MIN_Y 6
#define MESH_MAX_Y 202
// Mesh upsample definition
#define MESH_NUM_X_POINTS 7
#define MESH_NUM_Y_POINTS 7
// Mesh measure definition
#define MESH_MEAS_NUM_X_POINTS 3
#define MESH_MEAS_NUM_Y_POINTS 3
#define MESH_HOME_Z_CALIB 0.2
#define MESH_HOME_Z_SEARCH 5
#define X_PROBE_OFFSET_FROM_EXTRUDER 23 // Z probe to nozzle X offset: -left +right
#define Y_PROBE_OFFSET_FROM_EXTRUDER 9 // Z probe to nozzle Y offset: -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
#endif
// Bed Temperature Control
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
#define PIDTEMPBED
//
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// Bed temperature compensation settings
#define BED_OFFSET 10
#define BED_OFFSET_START 40
#define BED_OFFSET_CENTER 50
#ifdef PIDTEMPBED
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10)
#define DEFAULT_bedKp 126.13
#define DEFAULT_bedKi 4.30
#define DEFAULT_bedKd 924.76
//120v 250W silicone heater into 4mm borosilicate (MendelMax 1.5+)
//from pidautotune
// #define DEFAULT_bedKp 97.1
// #define DEFAULT_bedKi 1.41
// #define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
/*-----------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 215
#define PLA_PREHEAT_HPB_TEMP 55
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 0
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 5
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_BED 1
#endif //__CONFIGURATION_PRUSA_H

View File

@ -18,44 +18,72 @@ 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.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Direction inverting
#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 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 true // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E2_DIR true // for direct drive extruder v9 set to true, for geared extruder set to false
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS -2.2
#define MANUAL_Z_HOME_POS 0.2
#define MANUAL_Z_HOME_POS 0.15
// Travel limits after homing
#define X_MAX_POS 255
#define X_MAX_POS 250
#define X_MIN_POS 0
#define Y_MAX_POS 210
#define Y_MIN_POS -4
#define Y_MIN_POS -2.2
#define Z_MAX_POS 210
#define Z_MIN_POS 0.2
#define Z_MIN_POS 0.15
// Canceled home position
#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)
#define DEFAULT_MAX_FEEDRATE {500, 500, 1000, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,1000,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,500,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 1500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1500 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 1000, 100} // set the speeds for manual moves (mm/min)
@ -73,15 +101,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
@ -94,19 +133,17 @@ EXTRUDER SETTINGS
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
#ifdef SNMM
//#define BOWDEN_LENGTH 408
#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_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
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
//#define DIS //for measuring bed heigth and PINDa detection heigth relative to auto home point, experimental function
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E70 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
@ -142,11 +179,12 @@ ADDITIONAL FEATURES SETTINGS
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#define FILAMENT_RUNOUT_SCRIPT "M600"
#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
@ -160,10 +198,12 @@ MOTOR CURRENT SETTINGS
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#if MOTHERBOARD == 203 || MOTHERBOARD == 200
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 830, 450} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 830, 500} // {XY,Z,E}
#define Z_SILENT 0
#define Z_HIGH_POWER 200
#endif
/*------------------------------------
@ -190,7 +230,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
@ -226,9 +266,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
@ -244,6 +291,10 @@ BED SETTINGS
PREHEAT SETTINGS
*------------------------------------*/
#define FARM_PREHEAT_HOTEND_TEMP 250
#define FARM_PREHEAT_HPB_TEMP 40
#define FARM_PREHEAT_FAN_SPEED 0
#define PLA_PREHEAT_HOTEND_TEMP 215
#define PLA_PREHEAT_HPB_TEMP 55
#define PLA_PREHEAT_FAN_SPEED 0
@ -305,12 +356,71 @@ 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
#define MAX_BED_TEMP_CALIBRATION 50
#define MAX_HOTEND_TEMP_CALIBRATION 50
#define MAX_E_STEPS_PER_UNIT 250
#define MIN_E_STEPS_PER_UNIT 100
#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 NC_TIME 10 //time in s for periodic important status messages sending which needs reponse from monitoring
#define NC_BUTTON_LONG_PRESS 15 //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
#define END_FILE_SECTION 10000 //number of bytes from end of file used for checking if file is complete
#define M600_TIMEOUT 600 //seconds
#ifndef SNMM
#define SUPPORT_VERBOSITY
#endif
#endif //__CONFIGURATION_PRUSA_H

View File

@ -6,18 +6,17 @@
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "1_75mm_MK3"
#define FILAMENT_SIZE "1_75mm_MK25"
#define NOZZLE_TYPE "E3Dv6full"
// Developer flag
#define DEVELOPER
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
#define CUSTOM_MENDEL_NAME "Prusa i3 MK2.5"
// Electronics
#define MOTHERBOARD BOARD_EINY_0_3a
#define HAS_SECOND_SERIAL_PORT
#define MOTHERBOARD BOARD_RAMBO_MINI_1_3
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
@ -32,14 +31,21 @@
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280} //Extruder motor changed back to 200step type
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Direction inverting
#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 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 true // for direct drive extruder v9 set to true, for geared extruder set to false
#define INVERT_E2_DIR true // for direct drive extruder v9 set to true, for geared extruder set to false
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS -2.2
@ -49,8 +55,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define X_MAX_POS 255
#define X_MIN_POS 0
#define Y_MAX_POS 210
#define Y_MIN_POS -12 //orig -4
#define Z_MAX_POS 210
#define Y_MIN_POS -4 //orig -4
#define Z_MAX_POS 200
#define Z_MIN_POS 0.15
// Canceled home position
@ -65,95 +71,51 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#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
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_MAX_FEEDRATE {200, 200, 12, 120} // (mm/sec) max feedrate (M203)
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // (mm/sec^2) max acceleration (M201)
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
//#define MAX_SILENT_FEEDRATE 2700 //
//number of bytes from end of the file to start check
#define END_FILE_SECTION 10000
#define Z_AXIS_ALWAYS_ON 1
//DEBUG
#if 0
//#define DEBUG_BUILD
#ifdef DEBUG_BUILD
//#define _NO_ASM
#define DEBUG_DCODES //D codes
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
#define DEBUG_DISABLE_STARTMSGS //no startup messages
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
#define DEBUG_STACK_MONITOR //Stack monitor in stepper ISR
//#define DEBUG_FSENSOR_LOG //Reports fsensor status to serial
//#define DEBUG_CRASHDET_COUNTERS //Display crash-detection counters on LCD
//#define DEBUG_RESUME_PRINT //Resume/save print debug enable
//#define DEBUG_UVLO_AUTOMATIC_RECOVER // Power panic automatic recovery debug output
//#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
//#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
//#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
//#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
//#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
//#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
//#define DEBUG_DISABLE_STARTMSGS //no startup messages
//#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
//#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
//#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
//#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
//#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
//#define DEBUG_BLINK_ACTIVE
#endif
/*------------------------------------
TMC2130 default settings
*------------------------------------*/
#define TMC2130_FCLK 12000000 // fclk = 12MHz
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis (increased from 16 to 32)
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
#define TMC2130_PWM_GRAD_X 4 // PWMCONF
#define TMC2130_PWM_AMPL_X 200 // PWMCONF
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF
#define TMC2130_PWM_AMPL_Y 210 // PWMCONF
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
/* //not used
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
*/
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
#define TMC2130_THIGH 0 // THIGH - unused
#define TMC2130_TCOOLTHRS 239 // TCOOLTHRS - coolstep treshold
#define TMC2130_SG_HOMING 1 // stallguard homing
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
#define TMC2130_SG_THRS_X 0 // stallguard sensitivity for X axis
#define TMC2130_SG_THRS_Y 0 // stallguard sensitivity for Y axis
#define TMC2130_SG_THRS_Z 2 // stallguard sensitivity for Z axis
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
#define TMC2130_CURRENTS_R {13, 18, 20, 22} // default running currents for all axes
//#define TMC2130_DEBUG
//#define TMC2130_DEBUG_WR
//#define TMC2130_DEBUG_RD
//#define DEBUG_DISABLE_FANCHECK //disable fan check (no ISR INT7, check disabled)
//#define DEBUG_DISABLE_FSENSORCHECK //disable fsensor check (no ISR INT7, check disabled)
//#define DEBUG_DUMP_TO_2ND_SERIAL //dump received characters to 2nd serial line
//#define DEBUG_STEPPER_TIMER_MISSED // Stop on stepper timer overflow, beep and display a message.
//#define PLANNER_DIAGNOSTICS // Show the planner queue status on printer display.
#endif /* DEBUG_BUILD */
/*------------------------------------
@ -174,7 +136,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#endif
#define HEATER_1_MAXTEMP 305
#define HEATER_2_MAXTEMP 305
#define BED_MAXTEMP 150
#define BED_MAXTEMP 125
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
// Define PID constants for extruder with PT100
@ -192,7 +154,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#endif
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
#define EXTRUDE_MINTEMP 190
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
@ -202,6 +164,9 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
#define PAT9125
#define FANCHECK
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
@ -235,7 +200,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define FILAMENTCHANGE_XYFEED 50
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
//#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_RFEED 7000 / 60
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 15
@ -253,8 +219,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#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
@ -268,12 +234,21 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
#if MOTHERBOARD == 203 || MOTHERBOARD == 200
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT {270, 830, 450} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 830, 500} // {XY,Z,E}
#define Z_SILENT 0
#define Z_HIGH_POWER 200
#endif
/*------------------------------------
PAT9125 SETTINGS
*------------------------------------*/
#define PAT9125_XRES 0
#define PAT9125_YRES 255
/*------------------------------------
BED SETTINGS
*------------------------------------*/
@ -359,8 +334,12 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
PREHEAT SETTINGS
*------------------------------------*/
#define FARM_PREHEAT_HOTEND_TEMP 250
#define FARM_PREHEAT_HPB_TEMP 40
#define FARM_PREHEAT_FAN_SPEED 0
#define PLA_PREHEAT_HOTEND_TEMP 215
#define PLA_PREHEAT_HPB_TEMP 55
#define PLA_PREHEAT_HPB_TEMP 60
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
@ -375,11 +354,11 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_HOTEND_TEMP 230
#define PET_PREHEAT_HPB_TEMP 85
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HOTEND_TEMP 240
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
@ -441,7 +420,6 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TEMP_SENSOR_BED 1
#endif
#define TEMP_SENSOR_PINDA 1
#define TEMP_SENSOR_AMBIENT 2000
#define STACK_GUARD_TEST_VALUE 0xA2A2
@ -454,9 +432,13 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define Z_BABYSTEP_MIN -3999
#define Z_BABYSTEP_MAX 0
#define PINDA_PREHEAT_X 20
#define PINDA_PREHEAT_Y 60
#define PINDA_PREHEAT_Z 0.15
/*
#define PINDA_PREHEAT_X 70
#define PINDA_PREHEAT_Y -3
#define PINDA_PREHEAT_Z 1
#define PINDA_PREHEAT_Z 1*/
#define PINDA_HEAT_T 120 //time in s
#define PINDA_MIN_T 50
@ -472,7 +454,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define DEFAULT_PID_TEMP 210
#define MIN_PRINT_FAN_SPEED 50
#define MIN_PRINT_FAN_SPEED 75
#ifdef SNMM
#define DEFAULT_RETRACTION 4 //used for PINDA temp calibration and pause print
@ -480,6 +462,12 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define DEFAULT_RETRACTION 1 //used for PINDA temp calibration and pause print
#endif
#define UVLO_Z_AXIS_SHIFT 2
#define HEATBED_V2
#define M600_TIMEOUT 600 //seconds
#define TACH0PULLUP
//#define SUPPORT_VERBOSITY
#endif //__CONFIGURATION_PRUSA_H

View File

@ -16,8 +16,7 @@
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
// Electronics
#define MOTHERBOARD BOARD_EINY_0_4a
#define HAS_SECOND_SERIAL_PORT
#define MOTHERBOARD BOARD_EINSY_1_0a
// Uncomment the below for the E3D PT100 temperature sensor (with or without PT100 Amplifier)
@ -33,14 +32,22 @@
// Steps per unit {X,Y,Z,E}
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,560}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,560}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Direction inverting
#define INVERT_X_DIR true // 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_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
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS -2.2
@ -50,7 +57,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define X_MAX_POS 255
#define X_MIN_POS 0
#define Y_MAX_POS 210
#define Y_MIN_POS -12 //orig -4
#define Y_MIN_POS -4 //orig -4
#define Z_MAX_POS 210
#define Z_MIN_POS 0.15
@ -64,26 +71,52 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#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 {2500, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
#define HOMING_FEEDRATE {3000, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_MAX_FEEDRATE {200, 200, 12, 120} // (mm/sec) max feedrate (M203)
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // (mm/sec^2) max acceleration (M201)
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
//#define MAX_SILENT_FEEDRATE 2700 //
//Silent mode limits
#define SILENT_MAX_ACCEL 960 // max axxeleration in silent mode in mm/s^2
#define SILENT_MAX_ACCEL_ST (100*SILENT_MAX_ACCEL) // max accel in steps/s^2
#define SILENT_MAX_FEEDRATE 172 //max feedrate in mm/s, because mode switched to normal for homming , this value limits also homing, it should be greater (172mm/s=9600mm/min>2700mm/min)
//Normal mode limits
#define NORMAL_MAX_ACCEL 2500 // Y-axis max axxeleration in normal mode in mm/s^2
#define NORMAL_MAX_ACCEL_ST (100*NORMAL_MAX_ACCEL) // max accel in steps/s^2
#define NORMAL_MAX_FEEDRATE 200 //max feedrate in mm/s, because mode switched to normal for homming , this value limits also homing, it should be greater (172mm/s=9600mm/min>2700mm/min)
//#define SIMPLE_ACCEL_LIMIT //new limitation method for normal/silent
//number of bytes from end of the file to start check
#define END_FILE_SECTION 10000
#define Z_AXIS_ALWAYS_ON 1
// Automatic recovery after crash is detected
#define AUTOMATIC_RECOVERY_AFTER_CRASH
//DEBUG
// Disable some commands
#define _DISABLE_M42_M226
// Minimum ambient temperature limit to start triggering MINTEMP errors [C]
// this value is litlebit higher that real limit, because ambient termistor is on the board and is temperated from it,
// temperature inside the case is around 31C for ambient temperature 25C, when the printer is powered on long time and idle
// the real limit is 15C (same as MINTEMP limit), this is because 15C is end of scale for both used thermistors (bed, heater)
#define MINTEMP_MINAMBIENT 25
#define MINTEMP_MINAMBIENT_RAW 978
//#define DEBUG_BUILD
#ifdef DEBUG_BUILD
//#define _NO_ASM
#define DEBUG_DCODES //D codes
#if 1
#define DEBUG_STACK_MONITOR //Stack monitor in stepper ISR
//#define DEBUG_FSENSOR_LOG //Reports fsensor status to serial
//#define DEBUG_CRASHDET_COUNTERS //Display crash-detection counters on LCD
//#define DEBUG_RESUME_PRINT //Resume/save print debug enable
@ -99,11 +132,17 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
//#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
//#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
//#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
//#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
//#define DEBUG_BLINK_ACTIVE
#endif
//#define DEBUG_DISABLE_FANCHECK //disable fan check (no ISR INT7, check disabled)
//#define DEBUG_DISABLE_FSENSORCHECK //disable fsensor check (no ISR INT7, check disabled)
#define DEBUG_DUMP_TO_2ND_SERIAL //dump received characters to 2nd serial line
#define DEBUG_STEPPER_TIMER_MISSED // Stop on stepper timer overflow, beep and display a message.
#define PLANNER_DIAGNOSTICS // Show the planner queue status on printer display.
#endif /* DEBUG_BUILD */
/*------------------------------------
TMC2130 default settings
@ -113,7 +152,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
#define TMC2130_USTEPS_E 64 // microstep resolution for E axis
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
@ -128,16 +167,28 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
/* //not used
#define TMC2130_PWM_GRAD_E 2 // PWMCONF
#define TMC2130_PWM_AMPL_E 235 // PWMCONF
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
#define TMC2130_PWM_AMPL_E 240 // PWMCONF
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
*/
#define TMC2130_TOFF_XYZ 3 // CHOPCONF // fchop = 27.778kHz
#define TMC2130_TOFF_E 3 // CHOPCONF // fchop = 27.778kHz
//#define TMC2130_TOFF_E 4 // CHOPCONF // fchop = 21.429kHz
//#define TMC2130_TOFF_E 5 // CHOPCONF // fchop = 17.442kHz
//#define TMC2130_STEALTH_E // Extruder stealthChop mode
//#define TMC2130_CNSTOFF_E // Extruder constant-off-time mode (similar to MK2)
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
@ -154,17 +205,15 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define TMC2130_TCOOLTHRS_E 500 // TCOOLTHRS - coolstep treshold
#define TMC2130_SG_HOMING 1 // stallguard homing
//#define TMC2130_SG_HOMING_SW_XY 1 // stallguard "software" homing for XY axes
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
#define TMC2130_SG_THRS_X 1 // stallguard sensitivity for X axis
#define TMC2130_SG_THRS_X 3 // stallguard sensitivity for X axis
#define TMC2130_SG_THRS_Y 3 // stallguard sensitivity for Y axis
#define TMC2130_SG_THRS_Z 3 // stallguard sensitivity for Z axis
#define TMC2130_SG_THRS_E 3 // stallguard sensitivity for E axis
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
#define TMC2130_CURRENTS_H {3, 3, 20, 28} // default holding currents for all axes
#define TMC2130_CURRENTS_R {13, 20, 20, 28} // default running currents for all axes
#define TMC2130_CURRENTS_H {13, 20, 25, 35} // default holding currents for all axes
#define TMC2130_CURRENTS_R {13, 20, 25, 35} // default running currents for all axes
#define TMC2130_UNLOAD_CURRENT_R 12 // lowe current for M600 to protect filament sensor
//#define TMC2130_DEBUG
//#define TMC2130_DEBUG_WR
@ -189,7 +238,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#endif
#define HEATER_1_MAXTEMP 305
#define HEATER_2_MAXTEMP 305
#define BED_MAXTEMP 150
#define BED_MAXTEMP 125
#if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
// Define PID constants for extruder with PT100
@ -207,7 +256,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#endif
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
#define EXTRUDE_MINTEMP 190
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
@ -217,6 +266,9 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
#define PAT9125
#define FANCHECK
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
@ -269,8 +321,8 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#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
@ -284,12 +336,19 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 310
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
#endif
/*------------------------------------
PAT9125 SETTINGS
*------------------------------------*/
#define PAT9125_XRES 0
#define PAT9125_YRES 255
/*------------------------------------
BED SETTINGS
*------------------------------------*/
@ -317,7 +376,7 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#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
#define Y_PROBE_OFFSET_FROM_EXTRUDER 5 // Z probe to nozzle Y offset: -front +behind
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
#endif
@ -375,8 +434,12 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
PREHEAT SETTINGS
*------------------------------------*/
#define FARM_PREHEAT_HOTEND_TEMP 250
#define FARM_PREHEAT_HPB_TEMP 40
#define FARM_PREHEAT_FAN_SPEED 0
#define PLA_PREHEAT_HOTEND_TEMP 215
#define PLA_PREHEAT_HPB_TEMP 55
#define PLA_PREHEAT_HPB_TEMP 60
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
@ -391,11 +454,11 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_HOTEND_TEMP 230
#define PET_PREHEAT_HPB_TEMP 85
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HOTEND_TEMP 240
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
@ -470,9 +533,13 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
#define Z_BABYSTEP_MIN -3999
#define Z_BABYSTEP_MAX 0
#define PINDA_PREHEAT_X 20
#define PINDA_PREHEAT_Y 60
#define PINDA_PREHEAT_Z 0.15
/*
#define PINDA_PREHEAT_X 70
#define PINDA_PREHEAT_Y -3
#define PINDA_PREHEAT_Z 1
#define PINDA_PREHEAT_Z 1*/
#define PINDA_HEAT_T 120 //time in s
#define PINDA_MIN_T 50
@ -502,12 +569,15 @@ const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic o
// For example, the Prusa i3 MK2 with 16 microsteps per full step has Z stepping of 400 microsteps per mm.
// At 400 microsteps per mm, a full step lifts the Z axis by 0.04mm, and a stepper driver cycle is 0.16mm.
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
#define UVLO_Z_AXIS_SHIFT 1.92
//#define UVLO_Z_AXIS_SHIFT 1.92
#define UVLO_Z_AXIS_SHIFT 0.64
// If power panic occured, and the current temperature is higher then target temperature before interrupt minus this offset, print will be recovered automatically.
#define AUTOMATIC_UVLO_BED_TEMP_OFFSET 5
#define HEATBED_V2
#define M600_TIMEOUT 600 //seconds
//#define SUPPORT_VERBOSITY
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,493 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "1_75mm_MK3"
#define NOZZLE_TYPE "E3Dv6full"
// Developer flag
#define DEVELOPER
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3 MK3"
// Electronics
#define MOTHERBOARD BOARD_EINY_0_4a
#define HAS_SECOND_SERIAL_PORT
// 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}
//#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,140}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/8,280}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS -2.2
#define MANUAL_Z_HOME_POS 0.2
// Travel limits after homing
#define X_MAX_POS 255
#define X_MIN_POS 0
#define Y_MAX_POS 210
#define Y_MIN_POS -12 //orig -4
#define Z_MAX_POS 210
#define Z_MIN_POS 0.15
// Canceled home position
#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 {2500, 3000, 800, 0} // set the homing speeds (mm/min) // 3000 is also valid for stallGuard homing. Valid range: 2200 - 3000
//#define DEFAULT_MAX_FEEDRATE {400, 400, 12, 120} // (mm/sec)
#define DEFAULT_MAX_FEEDRATE {500, 500, 12, 120} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {1000, 1000, 200, 5000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 1250 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {2700, 2700, 1000, 100} // set the speeds for manual moves (mm/min)
//#define MAX_SILENT_FEEDRATE 2700 //
#define Z_AXIS_ALWAYS_ON 1
//DEBUG
#define DEBUG_DCODES //D codes
#if 0
#define DEBUG_DISABLE_XMINLIMIT //x min limit ignored
#define DEBUG_DISABLE_XMAXLIMIT //x max limit ignored
#define DEBUG_DISABLE_YMINLIMIT //y min limit ignored
#define DEBUG_DISABLE_YMAXLIMIT //y max limit ignored
#define DEBUG_DISABLE_ZMINLIMIT //z min limit ignored
#define DEBUG_DISABLE_ZMAXLIMIT //z max limit ignored
#define DEBUG_DISABLE_STARTMSGS //no startup messages
#define DEBUG_DISABLE_MINTEMP //mintemp error ignored
#define DEBUG_DISABLE_SWLIMITS //sw limits ignored
#define DEBUG_DISABLE_LCD_STATUS_LINE //empty four lcd line
#define DEBUG_DISABLE_PREVENT_EXTRUDER //cold extrusion and long extrusion allowed
#define DEBUG_DISABLE_PRUSA_STATISTICS //disable prusa_statistics() mesages
//#define DEBUG_XSTEP_DUP_PIN 21 //duplicate x-step output to pin 21 (SCL on P3)
//#define DEBUG_YSTEP_DUP_PIN 21 //duplicate y-step output to pin 21 (SCL on P3)
//#define DEBUG_BLINK_ACTIVE
#endif
/*------------------------------------
TMC2130 default settings
*------------------------------------*/
#define TMC2130_FCLK 12000000 // fclk = 12MHz
#define TMC2130_USTEPS_XY 16 // microstep resolution for XY axes
#define TMC2130_USTEPS_Z 16 // microstep resolution for Z axis
#define TMC2130_USTEPS_E 32 // microstep resolution for E axis
#define TMC2130_INTPOL_XY 1 // extrapolate 256 for XY axes
#define TMC2130_INTPOL_Z 1 // extrapolate 256 for Z axis
#define TMC2130_INTPOL_E 1 // extrapolate 256 for E axis
#define TMC2130_PWM_GRAD_X 4 // PWMCONF
#define TMC2130_PWM_AMPL_X 200 // PWMCONF
#define TMC2130_PWM_AUTO_X 1 // PWMCONF
#define TMC2130_PWM_FREQ_X 2 // PWMCONF
#define TMC2130_PWM_GRAD_Y 4 // PWMCONF
#define TMC2130_PWM_AMPL_Y 215 // PWMCONF
#define TMC2130_PWM_AUTO_Y 1 // PWMCONF
#define TMC2130_PWM_FREQ_Y 2 // PWMCONF
/* //not used
#define TMC2130_PWM_GRAD_Z 4 // PWMCONF
#define TMC2130_PWM_AMPL_Z 200 // PWMCONF
#define TMC2130_PWM_AUTO_Z 1 // PWMCONF
#define TMC2130_PWM_FREQ_Z 2 // PWMCONF
#define TMC2130_PWM_GRAD_E 4 // PWMCONF
#define TMC2130_PWM_AMPL_E 200 // PWMCONF
#define TMC2130_PWM_AUTO_E 1 // PWMCONF
#define TMC2130_PWM_FREQ_E 2 // PWMCONF
*/
//#define TMC2130_PWM_DIV 683 // PWM frequency divider (1024, 683, 512, 410)
#define TMC2130_PWM_DIV 512 // PWM frequency divider (1024, 683, 512, 410)
#define TMC2130_PWM_CLK (2 * TMC2130_FCLK / TMC2130_PWM_DIV) // PWM frequency (23.4kHz, 35.1kHz, 46.9kHz, 58.5kHz for 12MHz fclk)
#define TMC2130_TPWMTHRS 0 // TPWMTHRS - Sets the switching speed threshold based on TSTEP from stealthChop to spreadCycle mode
#define TMC2130_THIGH 0 // THIGH - unused
#define TMC2130_TCOOLTHRS 500 // TCOOLTHRS - coolstep treshold
#define TMC2130_SG_HOMING 1 // stallguard homing
#define TMC2130_SG_HOMING_SW_Z 1 // stallguard "software" homing for Z axis
#define TMC2130_SG_THRS_X 6 // stallguard sensitivity for X axis
#define TMC2130_SG_THRS_Y 6 // stallguard sensitivity for Y axis
#define TMC2130_SG_THRS_Z 3 // stallguard sensitivity for Z axis
#define TMC2130_SG_DELTA 128 // stallguard delta [usteps] (minimum usteps before stallguard readed - SW homing)
//new settings is possible for vsense = 1, running current value > 31 set vsense to zero and shift both currents by 1 bit right (Z axis only)
#define TMC2130_CURRENTS_H {3, 3, 5, 8} // default holding currents for all axes
#define TMC2130_CURRENTS_R {13, 31, 20, 22} // default running currents for all axes
//#define TMC2130_DEBUG
//#define TMC2130_DEBUG_WR
//#define TMC2130_DEBUG_RD
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#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
#define DEFAULT_Kp 16.13
#define DEFAULT_Ki 1.1625
#define DEFAULT_Kd 56.23
#endif
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 8
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E70 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F7000"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 50
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 15
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 200 || MOTHERBOARD == 203 || MOTHERBOARD == 303 || MOTHERBOARD == 304 || MOTHERBOARD == 305
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {400, 750, 750} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {400, 750, 750} // {XY,Z,E}
#endif
/*------------------------------------
BED SETTINGS
*------------------------------------*/
// Define Mesh Bed Leveling system to enable it
#define MESH_BED_LEVELING
#ifdef MESH_BED_LEVELING
#define MBL_Z_STEP 0.01
// Mesh definitions
#define MESH_MIN_X 35
#define MESH_MAX_X 238
#define MESH_MIN_Y 6
#define MESH_MAX_Y 202
// Mesh upsample definition
#define MESH_NUM_X_POINTS 7
#define MESH_NUM_Y_POINTS 7
// Mesh measure definition
#define MESH_MEAS_NUM_X_POINTS 3
#define MESH_MEAS_NUM_Y_POINTS 3
#define MESH_HOME_Z_CALIB 0.2
#define MESH_HOME_Z_SEARCH 5 //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
#define Z_PROBE_OFFSET_FROM_EXTRUDER -0.4 // Z probe to nozzle Z offset: -below (always!)
#endif
// Bed Temperature Control
// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis
//
// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder.
// If your PID_dT above is the default, and correct for your hardware/configuration, that means 7.689Hz,
// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating.
// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use bed PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
#define PIDTEMPBED
//
//#define BED_LIMIT_SWITCHING
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// Bed temperature compensation settings
#define BED_OFFSET 10
#define BED_OFFSET_START 40
#define BED_OFFSET_CENTER 50
#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
// #define DEFAULT_bedKp 97.1
// #define DEFAULT_bedKi 1.41
// #define DEFAULT_bedKd 1675.16
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
#endif // PIDTEMPBED
/*-----------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 215
#define PLA_PREHEAT_HPB_TEMP 55
#define PLA_PREHEAT_FAN_SPEED 0
#define ABS_PREHEAT_HOTEND_TEMP 255
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 0
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 230
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 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 TEMP_SENSOR_PINDA 1
#define TEMP_SENSOR_AMBIENT 2000
#define STACK_GUARD_TEST_VALUE 0xA2A2
#define MAX_BED_TEMP_CALIBRATION 50
#define MAX_HOTEND_TEMP_CALIBRATION 50
#define MAX_E_STEPS_PER_UNIT 250
#define MIN_E_STEPS_PER_UNIT 100
#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 75
#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
// How much shall the print head be lifted on power panic?
// Ideally the Z axis will reach a zero phase of the stepper driver on power outage. To simplify this,
// UVLO_Z_AXIS_SHIFT shall be an integer multiply of the stepper driver cycle, that is 4x full step.
// For example, the Prusa i3 MK2 with 16 microsteps per full step has Z stepping of 400 microsteps per mm.
// At 400 microsteps per mm, a full step lifts the Z axis by 0.04mm, and a stepper driver cycle is 0.16mm.
// The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm.
#define UVLO_Z_AXIS_SHIFT 1.92
#define HEATBED_V2
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,247 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "3mm"
#define NOZZLE_TYPE "PrusaNmk2"
#define THREEMM_PRINTER
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3"
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_0
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/0.8,350*1.5}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 0.25
// Travel limits after homing
#define X_MAX_POS 214
#define X_MIN_POS 0
#define Y_MAX_POS 198
#define Y_MIN_POS 0
#define Z_MAX_POS 201
#define Z_MIN_POS 0.23
// Canceled home position
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 180
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
#define DEFAULT_MAX_FEEDRATE {500, 500, 3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 240, 60} // set the speeds for manual moves (mm/min)
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 15
// Maxtemps
#define HEATER_0_MAXTEMP 315
#define HEATER_1_MAXTEMP 275
#define HEATER_2_MAXTEMP 275
#define BED_MAXTEMP 150
// Define PID constants for extruder
#define DEFAULT_Kp 12.7
#define DEFAULT_Ki 1.09
#define DEFAULT_Kd 37.4
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 6
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E65 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 70
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 300
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 450, 850} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 450, 500} // {XY,Z,E}
#endif
/*------------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 220
#define PLA_PREHEAT_HPB_TEMP 50
#define PLA_PREHEAT_FAN_SPEED 255
#define ABS_PREHEAT_HOTEND_TEMP 285
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 250
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_BED 1
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,246 +0,0 @@
#ifndef CONFIGURATION_PRUSA_H
#define CONFIGURATION_PRUSA_H
/*------------------------------------
GENERAL SETTINGS
*------------------------------------*/
// Printer revision
#define FILAMENT_SIZE "3mm"
#define NOZZLE_TYPE "PrusaNmk2"
#define THREEMM_PRINTER
// Printer name
#define CUSTOM_MENDEL_NAME "Prusa i3"
// Electronics
#define MOTHERBOARD BOARD_RAMBO_MINI_1_3
/*------------------------------------
AXIS SETTINGS
*------------------------------------*/
// Steps per unit {X,Y,Z,E}
#define DEFAULT_AXIS_STEPS_PER_UNIT {100,100,3200/0.8,350*1.5}
// Endstop inverting
const bool X_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Y_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
const bool Z_MIN_ENDSTOP_INVERTING = false; // set to true to invert the logic of the endstop.
// Home position
#define MANUAL_X_HOME_POS 0
#define MANUAL_Y_HOME_POS 0
#define MANUAL_Z_HOME_POS 0.25
// Travel limits after homing
#define X_MAX_POS 214
#define X_MIN_POS 0
#define Y_MAX_POS 198
#define Y_MIN_POS 0
#define Z_MAX_POS 201
#define Z_MIN_POS 0.23
// Canceled home position
#define X_CANCEL_POS 50
#define Y_CANCEL_POS 180
#define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
#define HOMING_FEEDRATE {3000, 3000, 240, 0} // set the homing speeds (mm/min)
#define DEFAULT_MAX_FEEDRATE {500, 500, 3, 25} // (mm/sec)
#define DEFAULT_MAX_ACCELERATION {9000,9000,30,10000} // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
#define DEFAULT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
#define DEFAULT_RETRACT_ACCELERATION 3000 // X, Y, Z and E max acceleration in mm/s^2 for retracts
#define MANUAL_FEEDRATE {3000, 3000, 240, 60} // set the speeds for manual moves (mm/min)
/*------------------------------------
EXTRUDER SETTINGS
*------------------------------------*/
// Mintemps
#define HEATER_0_MINTEMP 15
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 15
// Maxtemps
#define HEATER_0_MAXTEMP 315
#define HEATER_1_MAXTEMP 275
#define HEATER_2_MAXTEMP 275
#define BED_MAXTEMP 150
// Define PID constants for extruder
#define DEFAULT_Kp 12.7
#define DEFAULT_Ki 1.09
#define DEFAULT_Kd 37.4
// Extrude mintemp
#define EXTRUDE_MINTEMP 130
// Extruder cooling fans
#define EXTRUDER_0_AUTO_FAN_PIN 6
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
/*------------------------------------
LOAD/UNLOAD FILAMENT SETTINGS
*------------------------------------*/
// Load filament commands
#define LOAD_FILAMENT_0 "M83"
#define LOAD_FILAMENT_1 "G1 E65 F400"
#define LOAD_FILAMENT_2 "G1 E40 F100"
// Unload filament commands
#define UNLOAD_FILAMENT_0 "M83"
#define UNLOAD_FILAMENT_1 "G1 E-80 F400"
/*------------------------------------
CHANGE FILAMENT SETTINGS
*------------------------------------*/
// Filament change configuration
#define FILAMENTCHANGEENABLE
#ifdef FILAMENTCHANGEENABLE
#define FILAMENTCHANGE_XPOS 211
#define FILAMENTCHANGE_YPOS 0
#define FILAMENTCHANGE_ZADD 2
#define FILAMENTCHANGE_FIRSTRETRACT -2
#define FILAMENTCHANGE_FINALRETRACT -80
#define FILAMENTCHANGE_FIRSTFEED 70
#define FILAMENTCHANGE_FINALFEED 50
#define FILAMENTCHANGE_RECFEED 5
#define FILAMENTCHANGE_XYFEED 70
#define FILAMENTCHANGE_EFEED 20
#define FILAMENTCHANGE_RFEED 400
#define FILAMENTCHANGE_EXFEED 2
#define FILAMENTCHANGE_ZFEED 300
#endif
/*------------------------------------
ADDITIONAL FEATURES SETTINGS
*------------------------------------*/
// Define Prusa filament runout sensor
//#define FILAMENT_RUNOUT_SUPPORT
#ifdef FILAMENT_RUNOUT_SUPPORT
#define FILAMENT_RUNOUT_SENSOR 1
#endif
/*------------------------------------
MOTOR CURRENT SETTINGS
*------------------------------------*/
// Motor Current setting for BIG RAMBo
#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A)
#define DIGIPOT_MOTOR_CURRENT_LOUD {135,135,135,135,135}
// Motor Current settings for RAMBo mini PWM value = MotorCurrentSetting * 255 / range
#if MOTHERBOARD == 102 || MOTHERBOARD == 302
#define MOTOR_CURRENT_PWM_RANGE 2000
#define DEFAULT_PWM_MOTOR_CURRENT {270, 450, 850} // {XY,Z,E}
#define DEFAULT_PWM_MOTOR_CURRENT_LOUD {540, 450, 500} // {XY,Z,E}
#endif
/*------------------------------------
PREHEAT SETTINGS
*------------------------------------*/
#define PLA_PREHEAT_HOTEND_TEMP 220
#define PLA_PREHEAT_HPB_TEMP 50
#define PLA_PREHEAT_FAN_SPEED 255
#define ABS_PREHEAT_HOTEND_TEMP 285
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255
#define HIPS_PREHEAT_HOTEND_TEMP 220
#define HIPS_PREHEAT_HPB_TEMP 100
#define HIPS_PREHEAT_FAN_SPEED 0
#define PP_PREHEAT_HOTEND_TEMP 254
#define PP_PREHEAT_HPB_TEMP 100
#define PP_PREHEAT_FAN_SPEED 0
#define PET_PREHEAT_HOTEND_TEMP 240
#define PET_PREHEAT_HPB_TEMP 90
#define PET_PREHEAT_FAN_SPEED 0
#define FLEX_PREHEAT_HOTEND_TEMP 250
#define FLEX_PREHEAT_HPB_TEMP 50
#define FLEX_PREHEAT_FAN_SPEED 0
// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option.
// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED)
#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current
// temperature runaway
//#define TEMP_RUNAWAY_BED_HYSTERESIS 5
//#define TEMP_RUNAWAY_BED_TIMEOUT 360
#define TEMP_RUNAWAY_EXTRUDER_HYSTERESIS 15
#define TEMP_RUNAWAY_EXTRUDER_TIMEOUT 45
/*------------------------------------
THERMISTORS SETTINGS
*------------------------------------*/
//
//--NORMAL IS 4.7kohm PULLUP!-- 1kohm pullup can be used on hotend sensor, using correct resistor and table
//
//// Temperature sensor settings:
// -2 is thermocouple with MAX6675 (only for sensor 0)
// -1 is thermocouple with AD595
// 0 is not used
// 1 is 100k thermistor - best choice for EPCOS 100k (4.7k pullup)
// 2 is 200k thermistor - ATC Semitec 204GT-2 (4.7k pullup)
// 3 is Mendel-parts thermistor (4.7k pullup)
// 4 is 10k thermistor !! do not use it for a hotend. It gives bad resolution at high temp. !!
// 5 is 100K thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (4.7k pullup)
// 6 is 100k EPCOS - Not as accurate as table 1 (created using a fluke thermocouple) (4.7k pullup)
// 7 is 100k Honeywell thermistor 135-104LAG-J01 (4.7k pullup)
// 71 is 100k Honeywell thermistor 135-104LAF-J01 (4.7k pullup)
// 8 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
// 9 is 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
// 10 is 100k RS thermistor 198-961 (4.7k pullup)
// 11 is 100k beta 3950 1% thermistor (4.7k pullup)
// 12 is 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
// 13 is 100k Hisens 3950 1% up to 300°C for hotend "Simple ONE " & "Hotend "All In ONE"
// 20 is the PT100 circuit found in the Ultimainboard V2.x
// 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950
//
// 1k ohm pullup tables - This is not normal, you would have to have changed out your 4.7k for 1k
// (but gives greater accuracy and more stable PID)
// 51 is 100k thermistor - EPCOS (1k pullup)
// 52 is 200k thermistor - ATC Semitec 204GT-2 (1k pullup)
// 55 is 100k thermistor - ATC Semitec 104GT-2 (Used in ParCan & J-Head) (1k pullup)
//
// 1047 is Pt1000 with 4k7 pullup
// 1010 is Pt1000 with 1k pullup (non standard)
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_BED 1
#endif //__CONFIGURATION_PRUSA_H

View File

@ -1,56 +0,0 @@
#include "Marlin.h"
#ifdef USE_WATCHDOG
#include <avr/wdt.h>
#include "watchdog.h"
#include "ultralcd.h"
//===========================================================================
//=============================private variables ============================
//===========================================================================
//===========================================================================
//=============================functinos ============================
//===========================================================================
/// intialise watch dog with a 4 sec interrupt time
void watchdog_init()
{
#ifdef WATCHDOG_RESET_MANUAL
//We enable the watchdog timer, but only for the interrupt.
//Take care, as this requires the correct order of operation, with interrupts disabled. See the datasheet of any AVR chip for details.
wdt_reset();
_WD_CONTROL_REG = _BV(_WD_CHANGE_BIT) | _BV(WDE);
_WD_CONTROL_REG = _BV(WDIE) | WDTO_4S;
#else
wdt_enable(WDTO_4S);
#endif
}
/// reset watchdog. MUST be called every 1s after init or avr will reset.
void watchdog_reset()
{
wdt_reset();
}
//===========================================================================
//=============================ISR ============================
//===========================================================================
//Watchdog timer interrupt, called if main program blocks >1sec and manual reset is enabled.
#ifdef WATCHDOG_RESET_MANUAL
ISR(WDT_vect)
{
//TODO: This message gets overwritten by the kill() call
LCD_ALERTMESSAGEPGM("ERR:Please Reset");//16 characters so it fits on a 16x2 display
lcd_update();
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer.");
kill(); //kill blocks
while(1); //wait for user or serial reset
}
#endif//RESET_MANUAL
#endif//USE_WATCHDOG

View File

@ -1,17 +0,0 @@
#ifndef WATCHDOG_H
#define WATCHDOG_H
#include "Marlin.h"
#ifdef USE_WATCHDOG
// initialize watch dog with a 1 sec interrupt time
void watchdog_init();
// pad the dog/reset watchdog. MUST be called at least every second after the first watchdog_init or AVR will go into emergency procedures..
void watchdog_reset();
#else
//If we do not have a watchdog, then we can have empty functions which are optimized away.
FORCE_INLINE void watchdog_init() {};
FORCE_INLINE void watchdog_reset() {};
#endif
#endif

View File

@ -568,10 +568,10 @@ uint8_t xyzcal_xycoords2point(int16_t x, int16_t y)
}
//MK3
#if ((MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#if ((MOTHERBOARD == 310))
const int16_t PROGMEM xyzcal_point_xcoords[4] = {1200, 22000, 22000, 1200};
const int16_t PROGMEM xyzcal_point_ycoords[4] = {600, 600, 19800, 19800};
#endif //((MOTHERBOARD == 303) || (MOTHERBOARD == 304))
#endif //((MOTHERBOARD == 310))
//MK2.5
#if ((MOTHERBOARD == 200) || (MOTHERBOARD == 203))

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff