Add 4th extruder

2.0.x
MagoKimbra 10 years ago
parent 9552e59306
commit 986e723eeb

@ -44,7 +44,7 @@
// The following define selects which electronics board you have.
// Please choose the name from boards.h that matches your setup
#ifndef MOTHERBOARD
#define MOTHERBOARD BOARD_ULTIMAKER
#define MOTHERBOARD BOARD_AZTEEG_X3_PRO
#endif
// Define this to set a custom name for your generic Mendel,
@ -104,9 +104,10 @@
// 147 is Pt100 with 4k7 pullup
// 110 is Pt100 with 1k pullup (non standard)
#define TEMP_SENSOR_0 -1
#define TEMP_SENSOR_1 -1
#define TEMP_SENSOR_0 1
#define TEMP_SENSOR_1 0
#define TEMP_SENSOR_2 0
#define TEMP_SENSOR_3 0
#define TEMP_SENSOR_BED 0
// This makes temp sensor 1 a redundant sensor for sensor 0. If the temperatures difference between these sensors is to high the print will be aborted.
@ -121,20 +122,22 @@
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
// to check that the wiring to the thermistor is not broken.
// Otherwise this would lead to the heater being powered on all the time.
#define HEATER_0_MINTEMP 5
#define HEATER_1_MINTEMP 5
#define HEATER_2_MINTEMP 5
#define BED_MINTEMP 5
#define HEATER_0_MINTEMP 5 // degC
#define HEATER_1_MINTEMP 5 // degC
#define HEATER_2_MINTEMP 5 // degC
#define HEATER_3_MINTEMP 5 // degC
#define BED_MINTEMP 5 // degC
// When temperature exceeds max temp, your heater will be switched off.
// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure!
// You should use MINTEMP for thermistor short/failure protection.
#define HEATER_0_MAXTEMP 275
#define HEATER_1_MAXTEMP 275
#define HEATER_2_MAXTEMP 275
#define BED_MAXTEMP 150
#define HEATER_0_MAXTEMP 275 // degC
#define HEATER_1_MAXTEMP 275 // degC
#define HEATER_2_MAXTEMP 275 // degC
#define HEATER_3_MAXTEMP 275 // degC
#define BED_MAXTEMP 150 // degC
// If your bed has low resistance e.g. .6 ohm and throws the fuse you can duty cycle it to reduce the
// If your bed has low resistance e.g. 0.6 ohm and throws the fuse you can duty cycle it to reduce the
// average current. The value should be an integer and the heat bed will be turned on for 1 interval of
// HEATER_BED_DUTY_CYCLE_DIVIDER intervals.
//#define HEATER_BED_DUTY_CYCLE_DIVIDER 4
@ -221,7 +224,7 @@
//if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
#define PREVENT_LENGTHY_EXTRUDE
#define EXTRUDE_MINTEMP 170
#define EXTRUDE_MINTEMP 170 // degC
#define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
/*================== Thermal Runaway Protection ==============================
@ -325,6 +328,7 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
#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
#define INVERT_E3_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

@ -77,7 +77,7 @@ void Config_StoreSettings()
EEPROM_WRITE_VAR(i,zprobe_zoffset);
#ifdef PIDTEMP
float dummy = 0.0f;
for (int e = 0; e < 3; e++)
for (int e = 0; e < 4; e++)
{
if (e < EXTRUDERS)
{
@ -132,12 +132,15 @@ void Config_StoreSettings()
// Save filament sizes
EEPROM_WRITE_VAR(i, volumetric_enabled);
EEPROM_WRITE_VAR(i, filament_size[0]);
#if EXTRUDERS > 1
#if EXTRUDERS > 1
EEPROM_WRITE_VAR(i, filament_size[1]);
#if EXTRUDERS > 2
#if EXTRUDERS > 2
EEPROM_WRITE_VAR(i, filament_size[2]);
#endif//EXTRUDERS > 2
#endif//EXTRUDERS > 1
#if EXTRUDERS > 3
EEPROM_WRITE_VAR(i, filament_size[3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
char ver2[4]=EEPROM_VERSION;
i=EEPROM_OFFSET;
@ -280,8 +283,13 @@ SERIAL_ECHOLNPGM("Scaling factors:");
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 T2 D", filament_size[2]);
SERIAL_ECHOLN("");
#endif//EXTRUDERS > 2
#endif//EXTRUDERS > 1
#if EXTRUDERS > 3
SERIAL_ECHO_START;
SERIAL_ECHOPAIR(" M200 T3 D", filament_size[3]);
SERIAL_ECHOLN("");
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
} else {
SERIAL_ECHOLNPGM("Filament settings: Disabled");
}
@ -345,7 +353,7 @@ void Config_RetrieveSettings()
EEPROM_READ_VAR(i,zprobe_zoffset);
#ifdef PIDTEMP
float dummy = 0.0f;
for (int e = 0; e < 3; e++) // 3 = max extruders supported by marlin
for (int e = 0; e < 4; e++) // 4 = max extruders supported by marlin
{
if (e < EXTRUDERS)
{
@ -412,8 +420,11 @@ void Config_RetrieveSettings()
EEPROM_READ_VAR(i, filament_size[1]);
#if EXTRUDERS > 2
EEPROM_READ_VAR(i, filament_size[2]);
#endif//EXTRUDERS > 2
#endif//EXTRUDERS > 1
#if EXTRUDERS > 3
EEPROM_READ_VAR(i, filament_size[3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
calculate_volumetric_multipliers();
// Call updatePID (similar to when we have processed M301)
updatePID();
@ -517,8 +528,11 @@ void Config_ResetDefault()
filament_size[1] = DEFAULT_NOMINAL_FILAMENT_DIA;
#if EXTRUDERS > 2
filament_size[2] = DEFAULT_NOMINAL_FILAMENT_DIA;
#endif//EXTRUDERS > 2
#endif//EXTRUDERS > 1
#if EXTRUDERS > 3
filament_size[3] = DEFAULT_NOMINAL_FILAMENT_DIA;
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
calculate_volumetric_multipliers();
SERIAL_ECHO_START;

@ -75,9 +75,10 @@
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
// Multiple extruders can be assigned to the same pin in which case
// the fan will turn on when any selected extruder is above the threshold.
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_0_AUTO_FAN_PIN -1
#define EXTRUDER_1_AUTO_FAN_PIN -1
#define EXTRUDER_2_AUTO_FAN_PIN -1
#define EXTRUDER_3_AUTO_FAN_PIN -1
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
@ -483,6 +484,10 @@ const unsigned int dropsegments=5; //everything with less than this number of st
#define THERMISTORHEATER_2 TEMP_SENSOR_2
#define HEATER_2_USES_THERMISTOR
#endif
#if TEMP_SENSOR_3 > 0
#define THERMISTORHEATER_3 TEMP_SENSOR_3
#define HEATER_3_USES_THERMISTOR
#endif
#if TEMP_SENSOR_BED > 0
#define THERMISTORBED TEMP_SENSOR_BED
#define BED_USES_THERMISTOR
@ -496,6 +501,9 @@ const unsigned int dropsegments=5; //everything with less than this number of st
#if TEMP_SENSOR_2 == -1
#define HEATER_2_USES_AD595
#endif
#if TEMP_SENSOR_3 == -1
#define HEATER_3_USES_AD595
#endif
#if TEMP_SENSOR_BED == -1
#define BED_USES_AD595
#endif
@ -514,6 +522,10 @@ const unsigned int dropsegments=5; //everything with less than this number of st
#undef HEATER_2_MINTEMP
#undef HEATER_2_MAXTEMP
#endif
#if TEMP_SENSOR_3 == 0
#undef HEATER_3_MINTEMP
#undef HEATER_3_MAXTEMP
#endif
#if TEMP_SENSOR_BED == 0
#undef BED_MINTEMP
#undef BED_MAXTEMP

@ -170,6 +170,13 @@ void manage_inactivity(bool ignore_stepper_queue=false);
#define disable_e2() /* nothing */
#endif
#if (EXTRUDERS > 3) && defined(E3_ENABLE_PIN) && (E3_ENABLE_PIN > -1)
#define enable_e3() WRITE(E3_ENABLE_PIN, E_ENABLE_ON)
#define disable_e3() WRITE(E3_ENABLE_PIN,!E_ENABLE_ON)
#else
#define enable_e3() /* nothing */
#define disable_e3() /* nothing */
#endif
enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};

@ -212,6 +212,9 @@ int extruder_multiply[EXTRUDERS] = {100
, 100
#if EXTRUDERS > 2
, 100
#if EXTRUDERS > 3
, 100
#endif
#endif
#endif
};
@ -221,6 +224,9 @@ float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA
, DEFAULT_NOMINAL_FILAMENT_DIA
#if EXTRUDERS > 2
, DEFAULT_NOMINAL_FILAMENT_DIA
#if EXTRUDERS > 3
, DEFAULT_NOMINAL_FILAMENT_DIA
#endif
#endif
#endif
};
@ -229,6 +235,9 @@ float volumetric_multiplier[EXTRUDERS] = {1.0
, 1.0
#if EXTRUDERS > 2
, 1.0
#if EXTRUDERS > 3
, 1.0
#endif
#endif
#endif
};
@ -271,19 +280,25 @@ int EtoPPressure=0;
bool autoretract_enabled=false;
bool retracted[EXTRUDERS]={false
#if EXTRUDERS > 1
, false
#if EXTRUDERS > 2
, false
#endif
#endif
#if EXTRUDERS > 2
, false
#if EXTRUDERS > 3
, false
#endif
#endif
#endif
};
bool retracted_swap[EXTRUDERS]={false
#if EXTRUDERS > 1
, false
#if EXTRUDERS > 2
, false
#endif
#endif
#if EXTRUDERS > 2
, false
#if EXTRUDERS > 3
, false
#endif
#endif
#endif
};
float retract_length = RETRACT_LENGTH;
@ -293,7 +308,7 @@ int EtoPPressure=0;
float retract_recover_length = RETRACT_RECOVER_LENGTH;
float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP;
float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE;
#endif
#endif // FWRETRACT
#ifdef ULTIPANEL
#ifdef PS_DEFAULT_OFF
@ -582,8 +597,8 @@ void setup()
SERIAL_ECHOLNPGM(STRING_CONFIG_H_AUTHOR);
SERIAL_ECHOPGM("Compiled: ");
SERIAL_ECHOLNPGM(__DATE__);
#endif
#endif
#endif // STRING_CONFIG_H_AUTHOR
#endif // STRING_VERSION_CONFIG_H
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_FREE_MEMORY);
SERIAL_ECHO(freeMemory());
@ -2881,29 +2896,32 @@ Sigma_Exit:
float area = .0;
if(code_seen('D')) {
float diameter = (float)code_value();
if (diameter == 0.0) {
// setting any extruder filament size disables volumetric on the assumption that
// slicers either generate in extruder values as cubic mm or as as filament feeds
// for all extruders
volumetric_enabled = false;
} else {
float diameter = (float)code_value();
if (diameter == 0.0) {
// setting any extruder filament size disables volumetric on the assumption that
// slicers either generate in extruder values as cubic mm or as as filament feeds
// for all extruders
volumetric_enabled = false;
} else {
filament_size[tmp_extruder] = (float)code_value();
// make sure all extruders have some sane value for the filament size
filament_size[0] = (filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[0]);
#if EXTRUDERS > 1
filament_size[1] = (filament_size[1] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[1]);
#if EXTRUDERS > 2
filament_size[2] = (filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[2]);
#endif
#endif
volumetric_enabled = true;
}
// make sure all extruders have some sane value for the filament size
filament_size[0] = (filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[0]);
#if EXTRUDERS > 1
filament_size[1] = (filament_size[1] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[1]);
#if EXTRUDERS > 2
filament_size[2] = (filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[2]);
#if EXTRUDERS > 3
filament_size[3] = (filament_size[3] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
volumetric_enabled = true;
}
} else {
//reserved for setting filament diameter via UFID or filament measuring device
break;
}
calculate_volumetric_multipliers();
calculate_volumetric_multipliers();
}
break;
case 201: // M201
@ -3020,23 +3038,29 @@ Sigma_Exit:
{
autoretract_enabled=false;
retracted[0]=false;
#if EXTRUDERS > 1
retracted[1]=false;
#endif
#if EXTRUDERS > 2
retracted[2]=false;
#endif
#if EXTRUDERS > 1
retracted[1]=false;
#endif
#if EXTRUDERS > 2
retracted[2]=false;
#endif
#if EXTRUDERS > 3
retracted[3]=false;
#endif
}break;
case 1:
{
autoretract_enabled=true;
retracted[0]=false;
#if EXTRUDERS > 1
retracted[1]=false;
#endif
#if EXTRUDERS > 2
retracted[2]=false;
#endif
#if EXTRUDERS > 1
retracted[1]=false;
#endif
#if EXTRUDERS > 2
retracted[2]=false;
#endif
#if EXTRUDERS > 3
retracted[3]=false;
#endif
}break;
default:
SERIAL_ECHO_START;
@ -4680,7 +4704,10 @@ void calculate_volumetric_multipliers() {
volumetric_multiplier[1] = calculate_volumetric_multiplier(filament_size[1]);
#if EXTRUDERS > 2
volumetric_multiplier[2] = calculate_volumetric_multiplier(filament_size[2]);
#endif
#endif
#if EXTRUDERS > 3
volumetric_multiplier[3] = calculate_volumetric_multiplier(filament_size[3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
}

@ -21,14 +21,16 @@
#define MSG_PREHEAT_PLA0 "Preheat PLA 1"
#define MSG_PREHEAT_PLA1 "Preheat PLA 2"
#define MSG_PREHEAT_PLA2 "Preheat PLA 3"
#define MSG_PREHEAT_PLA012 "Preheat PLA All"
#define MSG_PREHEAT_PLA3 "Preheat PLA 4"
#define MSG_PREHEAT_PLA0123 "Preheat PLA All"
#define MSG_PREHEAT_PLA_BEDONLY "Preheat PLA Bed"
#define MSG_PREHEAT_PLA_SETTINGS "Preheat PLA conf"
#define MSG_PREHEAT_ABS "Preheat ABS"
#define MSG_PREHEAT_ABS0 "Preheat ABS 1"
#define MSG_PREHEAT_ABS1 "Preheat ABS 2"
#define MSG_PREHEAT_ABS2 "Preheat ABS 3"
#define MSG_PREHEAT_ABS012 "Preheat ABS All"
#define MSG_PREHEAT_ABS3 "Preheat ABS 4"
#define MSG_PREHEAT_ABS0123 "Preheat ABS All"
#define MSG_PREHEAT_ABS_BEDONLY "Preheat ABS Bed"
#define MSG_PREHEAT_ABS_SETTINGS "Preheat ABS conf"
#define MSG_COOLDOWN "Cooldown"
@ -43,6 +45,7 @@
#define MSG_MOVE_E "Extruder"
#define MSG_MOVE_E1 "Extruder2"
#define MSG_MOVE_E2 "Extruder3"
#define MSG_MOVE_E3 "Extruder4"
#define MSG_MOVE_01MM "Move 0.1mm"
#define MSG_MOVE_1MM "Move 1mm"
#define MSG_MOVE_10MM "Move 10mm"
@ -50,12 +53,14 @@
#define MSG_NOZZLE "Nozzle"
#define MSG_NOZZLE1 "Nozzle2"
#define MSG_NOZZLE2 "Nozzle3"
#define MSG_NOZZLE3 "Nozzle4"
#define MSG_BED "Bed"
#define MSG_FAN_SPEED "Fan speed"
#define MSG_FLOW "Flow"
#define MSG_FLOW0 "Flow 0"
#define MSG_FLOW1 "Flow 1"
#define MSG_FLOW2 "Flow 2"
#define MSG_FLOW3 "Flow 3"
#define MSG_CONTROL "Control"
#define MSG_MIN " \002 Min"
#define MSG_MAX " \002 Max"
@ -75,6 +80,10 @@
#define MSG_PID_I2 "PID-I E3"
#define MSG_PID_D2 "PID-D E3"
#define MSG_PID_C2 "PID-C E3"
#define MSG_PID_P3 "PID-P E4"
#define MSG_PID_I3 "PID-I E4"
#define MSG_PID_D3 "PID-D E4"
#define MSG_PID_C3 "PID-C E4"
#define MSG_ACC "Accel"
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
@ -99,6 +108,7 @@
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Fil. Dia. 1"
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Fil. Dia. 2"
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Fil. Dia. 3"
#define MSG_FILAMENT_SIZE_EXTRUDER_3 "Fil. Dia. 4"
#define MSG_CONTRAST "LCD contrast"
#define MSG_STORE_EPROM "Store memory"
#define MSG_LOAD_EPROM "Load memory"

@ -21,14 +21,16 @@
#define MSG_PREHEAT_PLA0 "Preriscalda PLA 1"
#define MSG_PREHEAT_PLA1 "Preriscalda PLA 2"
#define MSG_PREHEAT_PLA2 "Preriscalda PLA 3"
#define MSG_PREHEAT_PLA012 "Prer. PLA Tutto"
#define MSG_PREHEAT_PLA3 "Preriscalda PLA 4"
#define MSG_PREHEAT_PLA0123 "Prer. PLA Tutto"
#define MSG_PREHEAT_PLA_BEDONLY "Prer. PLA Piatto"
#define MSG_PREHEAT_PLA_SETTINGS "Config. prer. PLA"
#define MSG_PREHEAT_ABS "Preriscalda ABS"
#define MSG_PREHEAT_ABS0 "Preriscalda ABS 1"
#define MSG_PREHEAT_ABS1 "Preriscalda ABS 2"
#define MSG_PREHEAT_ABS2 "Preriscalda ABS 3"
#define MSG_PREHEAT_ABS012 "Prer. ABS Tutto"
#define MSG_PREHEAT_ABS3 "Preriscalda ABS 4"
#define MSG_PREHEAT_ABS0123 "Prer. ABS Tutto"
#define MSG_PREHEAT_ABS_BEDONLY "Prer. ABS Piatto"
#define MSG_PREHEAT_ABS_SETTINGS "Config. prer. ABS"
#define MSG_COOLDOWN "Raffredda"
@ -43,6 +45,7 @@
#define MSG_MOVE_E "Estrusore"
#define MSG_MOVE_E1 "Estrusore 2"
#define MSG_MOVE_E2 "Estrusore 3"
#define MSG_MOVE_E3 "Estrusore 4"
#define MSG_MOVE_01MM "Muovi di 0.1mm"
#define MSG_MOVE_1MM "Muovi di 1mm"
#define MSG_MOVE_10MM "Muovi di 10mm"
@ -50,12 +53,14 @@
#define MSG_NOZZLE "Ugello"
#define MSG_NOZZLE1 "Ugello2"
#define MSG_NOZZLE2 "Ugello3"
#define MSG_NOZZLE3 "Ugello4"
#define MSG_BED "Piatto"
#define MSG_FAN_SPEED "Ventola"
#define MSG_FLOW "Flusso"
#define MSG_FLOW0 "Flusso 0"
#define MSG_FLOW1 "Flusso 1"
#define MSG_FLOW2 "Flusso 2"
#define MSG_FLOW3 "Flusso 3"
#define MSG_CONTROL "Controllo"
#define MSG_MIN " \002 Min:"
#define MSG_MAX " \002 Max:"
@ -75,6 +80,10 @@
#define MSG_PID_I2 "PID-I E3"
#define MSG_PID_D2 "PID-D E3"
#define MSG_PID_C2 "PID-C E3"
#define MSG_PID_P3 "PID-P E4"
#define MSG_PID_I3 "PID-I E4"
#define MSG_PID_D3 "PID-D E4"
#define MSG_PID_C3 "PID-C E4"
#define MSG_ACC "Accel."
#define MSG_VXY_JERK "Vxy-jerk"
#define MSG_VZ_JERK "Vz-jerk"
@ -95,10 +104,11 @@
#define MSG_TEMPERATURE "Temperatura"
#define MSG_MOTION "Movimento"
#define MSG_VOLUMETRIC "Filament"
#define MSG_VOLUMETRIC_ENABLED "E in mm³"
#define MSG_VOLUMETRIC_ENABLED "E in mm³"
#define MSG_FILAMENT_SIZE_EXTRUDER_0 "Diam. filo 1"
#define MSG_FILAMENT_SIZE_EXTRUDER_1 "Diam. filo 2"
#define MSG_FILAMENT_SIZE_EXTRUDER_2 "Diam. filo 3"
#define MSG_FILAMENT_SIZE_EXTRUDER_3 "Diam. filo 4"
#define MSG_CONTRAST "Contrasto LCD"
#define MSG_STORE_EPROM "Salva in EEPROM"
#define MSG_LOAD_EPROM "Carica da EEPROM"

@ -2933,6 +2933,12 @@ Fan_2 2
#endif // CHEAPTRONIC
#ifndef HEATER_3_PIN
#define HEATER_3_PIN -1
#endif
#ifndef TEMP_3_PIN
#define TEMP_3_PIN -1
#endif
#ifndef KNOWN_BOARD
#error Unknown MOTHERBOARD value in configuration.h
@ -2950,6 +2956,11 @@ Fan_2 2
#else
#define _E2_PINS
#endif
#if EXTRUDERS > 3
#define _E3_PINS E3_STEP_PIN, E3_DIR_PIN, E3_ENABLE_PIN, HEATER_3_PIN,
#else
#define _E3_PINS
#endif
#ifdef X_STOP_PIN
#if X_HOME_DIR < 0
@ -2995,7 +3006,6 @@ Fan_2 2
#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, PS_ON_PIN, \
HEATER_BED_PIN, FAN_PIN, \
_E0_PINS _E1_PINS _E2_PINS \
analogInputToDigitalPin(TEMP_0_PIN), analogInputToDigitalPin(TEMP_1_PIN), analogInputToDigitalPin(TEMP_2_PIN), analogInputToDigitalPin(TEMP_BED_PIN) }
_E0_PINS _E1_PINS _E2_PINS _E3_PINS \
analogInputToDigitalPin(TEMP_0_PIN), analogInputToDigitalPin(TEMP_1_PIN), analogInputToDigitalPin(TEMP_2_PIN), analogInputToDigitalPin(TEMP_3_PIN), analogInputToDigitalPin(TEMP_BED_PIN) }
#endif //__PINS_H

@ -80,7 +80,7 @@ unsigned long axis_steps_per_sqr_second[NUM_AXIS];
matrix_3x3 plan_bed_level_matrix = {
1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0,
0.0, 0.0, 1.0
};
#endif // #ifdef ENABLE_AUTO_BED_LEVELING
@ -96,7 +96,7 @@ float autotemp_factor=0.1;
bool autotemp_enabled=false;
#endif
unsigned char g_uc_extruder_last_move[3] = {0,0,0};
unsigned char g_uc_extruder_last_move[4] = {0,0,0,0};
//===========================================================================
//=================semi-private variables, used in inline functions =====
@ -486,6 +486,7 @@ void check_axes_activity()
disable_e0();
disable_e1();
disable_e2();
disable_e3();
}
#if defined(FAN_PIN) && FAN_PIN > -1
#ifdef FAN_KICKSTART_TIME
@ -672,6 +673,7 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
if(g_uc_extruder_last_move[0] > 0) g_uc_extruder_last_move[0]--;
if(g_uc_extruder_last_move[1] > 0) g_uc_extruder_last_move[1]--;
if(g_uc_extruder_last_move[2] > 0) g_uc_extruder_last_move[2]--;
if(g_uc_extruder_last_move[3] > 0) g_uc_extruder_last_move[3]--;
switch(extruder)
{
@ -681,6 +683,7 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
if(g_uc_extruder_last_move[1] == 0) disable_e1();
if(g_uc_extruder_last_move[2] == 0) disable_e2();
if(g_uc_extruder_last_move[3] == 0) disable_e3();
break;
case 1:
enable_e1();
@ -688,6 +691,7 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
if(g_uc_extruder_last_move[0] == 0) disable_e0();
if(g_uc_extruder_last_move[2] == 0) disable_e2();
if(g_uc_extruder_last_move[3] == 0) disable_e3();
break;
case 2:
enable_e2();
@ -695,6 +699,15 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
if(g_uc_extruder_last_move[0] == 0) disable_e0();
if(g_uc_extruder_last_move[1] == 0) disable_e1();
if(g_uc_extruder_last_move[3] == 0) disable_e3();
break;
case 3:
enable_e3();
g_uc_extruder_last_move[3] = BLOCK_BUFFER_SIZE*2;
if(g_uc_extruder_last_move[0] == 0) disable_e0();
if(g_uc_extruder_last_move[1] == 0) disable_e1();
if(g_uc_extruder_last_move[2] == 0) disable_e2();
break;
}
}
@ -703,6 +716,7 @@ block->steps_y = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-positi
enable_e0();
enable_e1();
enable_e2();
enable_e3();
}
}
@ -866,7 +880,7 @@ Having the real displacement of the head, we can calculate the total movement le
long min_xy_segment_time =min(max_x_segment_time, max_y_segment_time);
if(min_xy_segment_time < MAX_FREQ_TIME)
speed_factor = min(speed_factor, speed_factor * (float)min_xy_segment_time / (float)MAX_FREQ_TIME);
#endif
#endif // XY_FREQUENCY_LIMIT
// Correct the speed
if( speed_factor < 1.0)

@ -55,7 +55,7 @@ volatile static unsigned long step_events_completed; // The number of step event
#ifdef ADVANCE
static long advance_rate, advance, final_advance = 0;
static long old_advance = 0;
static long e_steps[3];
static long e_steps[4];
#endif
static long acceleration_time, deceleration_time;
//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
@ -200,6 +200,8 @@ void checkHitEndstops()
setTargetHotend0(0);
setTargetHotend1(0);
setTargetHotend2(0);
setTargetHotend3(0);
setTargetBed(0);
}
#endif
}
@ -298,7 +300,7 @@ FORCE_INLINE void trapezoid_generator_reset() {
// SERIAL_ECHOPGM("advance rate :");
// SERIAL_ECHO(current_block->advance_rate/256.0);
// SERIAL_ECHOPGM("initial advance :");
// SERIAL_ECHO(current_block->initial_advance/256.0);
// SERIAL_ECHO(current_block->initial_advance/256.0);
// SERIAL_ECHOPGM("final advance :");
// SERIAL_ECHOLN(current_block->final_advance/256.0);
@ -552,8 +554,8 @@ ISR(TIMER1_COMPA_vect)
}
#endif //ADVANCE
counter_x += current_block->steps_x;
#ifdef CONFIG_STEPPERS_TOSHIBA
counter_x += current_block->steps_x;
#ifdef CONFIG_STEPPERS_TOSHIBA
/* The toshiba stepper controller require much longer pulses
* tjerfore we 'stage' decompose the pulses between high, and
* low instead of doing each in turn. The extra tests add enough
@ -681,7 +683,7 @@ ISR(TIMER1_COMPA_vect)
WRITE_E_STEP(INVERT_E_STEP_PIN);
}
#endif //!ADVANCE
#endif
#endif // CONFIG_STEPPERS_TOSHIBA
step_events_completed += 1;
if(step_events_completed >= current_block->step_event_count) break;
}
@ -807,6 +809,22 @@ ISR(TIMER1_COMPA_vect)
}
}
#endif
#if EXTRUDERS > 3
if (e_steps[3] != 0) {
WRITE(E3_STEP_PIN, INVERT_E_STEP_PIN);
if (e_steps[3] < 0) {
WRITE(E3_DIR_PIN, INVERT_E3_DIR);
e_steps[3]++;
WRITE(E3_STEP_PIN, !INVERT_E_STEP_PIN);
}
else if (e_steps[3] > 0) {
WRITE(E3_DIR_PIN, !INVERT_E3_DIR);
e_steps[3]--;
WRITE(E3_STEP_PIN, !INVERT_E_STEP_PIN);
}
}
#endif
}
}
#endif // ADVANCE
@ -846,6 +864,9 @@ void st_init()
#if defined(E2_DIR_PIN) && (E2_DIR_PIN > -1)
SET_OUTPUT(E2_DIR_PIN);
#endif
#if defined(E3_DIR_PIN) && (E3_DIR_PIN > -1)
SET_OUTPUT(E3_DIR_PIN);
#endif
//Initialize Enable Pins - steppers default to disabled.
@ -887,6 +908,10 @@ void st_init()
SET_OUTPUT(E2_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E2_ENABLE_PIN,HIGH);
#endif
#if defined(E3_ENABLE_PIN) && (E3_ENABLE_PIN > -1)
SET_OUTPUT(E3_ENABLE_PIN);
if(!E_ENABLE_ON) WRITE(E3_ENABLE_PIN,HIGH);
#endif
//endstops and pullups
@ -977,6 +1002,11 @@ void st_init()
WRITE(E2_STEP_PIN,INVERT_E_STEP_PIN);
disable_e2();
#endif
#if defined(E3_STEP_PIN) && (E3_STEP_PIN > -1)
SET_OUTPUT(E3_STEP_PIN);
WRITE(E3_STEP_PIN,INVERT_E_STEP_PIN);
disable_e3();
#endif
// waveform generation = 0100 = CTC
TCCR1B &= ~(1<<WGM13);
@ -1007,6 +1037,7 @@ void st_init()
e_steps[0] = 0;
e_steps[1] = 0;
e_steps[2] = 0;
e_steps[3] = 0;
TIMSK0 |= (1<<OCIE0A);
#endif //ADVANCE
@ -1068,6 +1099,7 @@ void finishAndDisableSteppers()
disable_e0();
disable_e1();
disable_e2();
disable_e3();
}
void quickStop()

@ -23,7 +23,11 @@
#include "planner.h"
#if EXTRUDERS > 2
#if EXTRUDERS > 3
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 3) { WRITE(E3_STEP_PIN, v); } else { if(current_block->active_extruder == 2) { WRITE(E2_STEP_PIN, v); } else { if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}}}
#define NORM_E_DIR() { if(current_block->active_extruder == 3) { WRITE(E3_DIR_PIN, !INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, !INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}}}
#define REV_E_DIR() { if(current_block->active_extruder == 3) { WRITE(E3_DIR_PIN, INVERT_E3_DIR); } else { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}}}
#elif EXTRUDERS > 2
#define WRITE_E_STEP(v) { if(current_block->active_extruder == 2) { WRITE(E2_STEP_PIN, v); } else { if(current_block->active_extruder == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}}
#define NORM_E_DIR() { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, !INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}}
#define REV_E_DIR() { if(current_block->active_extruder == 2) { WRITE(E2_DIR_PIN, INVERT_E2_DIR); } else { if(current_block->active_extruder == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}}

@ -115,14 +115,16 @@ static volatile bool temp_meas_ready = false;
static unsigned long extruder_autofan_last_check;
#endif
#if EXTRUDERS > 3
#if EXTRUDERS > 4
# error Unsupported number of extruders
#elif EXTRUDERS > 3
# define ARRAY_BY_EXTRUDERS(v1, v2, v3, v4) { v1, v2, v3, v4 }
#elif EXTRUDERS > 2
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2, v3 }
# define ARRAY_BY_EXTRUDERS(v1, v2, v3, v4) { v1, v2, v3 }
#elif EXTRUDERS > 1
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2 }
# define ARRAY_BY_EXTRUDERS(v1, v2, v3, v4) { v1, v2 }
#else
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1 }
# define ARRAY_BY_EXTRUDERS(v1, v2, v3, v4) { v1 }
#endif
#ifdef PIDTEMP
@ -144,10 +146,10 @@ static volatile bool temp_meas_ready = false;
#endif //PIDTEMP
// Init min and max temp with extreme values to prevent false errors during startup
static int minttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP );
static int maxttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP );
static int minttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 0, 0, 0 );
static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 16383, 16383, 16383 );
static int minttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP, HEATER_3_RAW_LO_TEMP);
static int maxttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP, HEATER_3_RAW_HI_TEMP);
static int minttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 0, 0, 0, 0 );
static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 16383, 16383, 16383, 16383 );
//static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP; /* No bed mintemp error implemented?!? */
#ifdef BED_MAXTEMP
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
@ -157,8 +159,8 @@ static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
static void *heater_ttbl_map[2] = {(void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE };
static uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN };
#else
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE, (void *)HEATER_3_TEMPTABLE );
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN, HEATER_3_TEMPTABLE_LEN );
#endif
static float analog2temp(int raw, uint8_t e);
@ -166,8 +168,8 @@ static float analog2tempBed(int raw);
static void updateTemperaturesFromRawValues();
#ifdef WATCH_TEMP_PERIOD
int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0,0);
unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0,0);
#endif //WATCH_TEMP_PERIOD
#ifndef SOFT_PWM_SCALE
@ -205,7 +207,8 @@ void PID_autotune(float temp, int extruder, int ncycles)
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_3_AUTO_FAN_PIN) && EXTRUDER_3_AUTO_FAN_PIN > -1)
unsigned long extruder_autofan_last_check = millis();
#endif
@ -248,7 +251,8 @@ void PID_autotune(float temp, int extruder, int ncycles)
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_3_AUTO_FAN_PIN) && EXTRUDER_3_AUTO_FAN_PIN > -1)
if(millis() - extruder_autofan_last_check > 2500) {
checkExtruderAutoFans();
extruder_autofan_last_check = millis();
@ -425,6 +429,19 @@ void checkExtruderAutoFans()
fanState |= 4;
}
#endif
#if defined(EXTRUDER_3_AUTO_FAN_PIN) && EXTRUDER_3_AUTO_FAN_PIN > -1
if (current_temperature[3] > EXTRUDER_AUTO_FAN_TEMPERATURE)
{
if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN)
fanState |= 1;
else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN)
fanState |= 2;
else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN)
fanState |= 4;
else
fanState |= 8;
}
#endif
// update extruder auto fan states
#if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
@ -439,6 +456,12 @@ void checkExtruderAutoFans()
&& EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0);
#endif
#if defined(EXTRUDER_3_AUTO_FAN_PIN) && EXTRUDER_3_AUTO_FAN_PIN > -1
if (EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN
&& EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
&& EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN)
setExtruderAutoFanState(EXTRUDER_3_AUTO_FAN_PIN, (fanState & 8) != 0);
#endif
}
#endif // any extruder auto fan pins set
@ -606,13 +629,13 @@ void manage_heater()
temp_dState_bed = pid_input;
pid_output = pTerm_bed + iTerm_bed - dTerm_bed;
if (pid_output > MAX_BED_POWER) {
if (pid_error_bed > 0 ) temp_iState_bed -= pid_error_bed; // conditional un-integration
pid_output=MAX_BED_POWER;
} else if (pid_output < 0){
if (pid_error_bed < 0 ) temp_iState_bed -= pid_error_bed; // conditional un-integration
pid_output=0;
}
if (pid_output > MAX_BED_POWER) {
if (pid_error_bed > 0 ) temp_iState_bed -= pid_error_bed; // conditional un-integration
pid_output=MAX_BED_POWER;
} else if (pid_output < 0){
if (pid_error_bed < 0 ) temp_iState_bed -= pid_error_bed; // conditional un-integration
pid_output=0;
}
#else
pid_output = constrain(target_temperature_bed, 0, MAX_BED_POWER);
@ -854,6 +877,9 @@ void tp_init()
#if defined(HEATER_2_PIN) && (HEATER_2_PIN > -1)
SET_OUTPUT(HEATER_2_PIN);
#endif
#if defined(HEATER_3_PIN) && (HEATER_3_PIN > -1)
SET_OUTPUT(HEATER_3_PIN);
#endif
#if defined(HEATER_BED_PIN) && (HEATER_BED_PIN > -1)
SET_OUTPUT(HEATER_BED_PIN);
#endif
@ -903,16 +929,23 @@ void tp_init()
#endif
#if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
#if TEMP_1_PIN < 8
DIDR0 |= 1<<TEMP_1_PIN;
DIDR0 |= 1<<TEMP_1_PIN;
#else
DIDR2 |= 1<<(TEMP_1_PIN - 8);
DIDR2 |= 1<<(TEMP_1_PIN - 8);
#endif
#endif
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
#if TEMP_2_PIN < 8
DIDR0 |= 1 << TEMP_2_PIN;
DIDR0 |= 1 << TEMP_2_PIN;
#else
DIDR2 |= 1<<(TEMP_2_PIN - 8);
DIDR2 |= 1<<(TEMP_2_PIN - 8);
#endif
#endif
#if defined(TEMP_3_PIN) && (TEMP_3_PIN > -1)
#if TEMP_3_PIN < 8
DIDR0 |= 1 << TEMP_3_PIN;
#else
DIDR2 |= 1<<(TEMP_3_PIN - 8);
#endif
#endif
#if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
@ -925,13 +958,13 @@ void tp_init()
//Added for Filament Sensor
#ifdef FILAMENT_SENSOR
#if defined(FILWIDTH_PIN) && (FILWIDTH_PIN > -1)
#if FILWIDTH_PIN < 8
DIDR0 |= 1<<FILWIDTH_PIN;
#else
DIDR2 |= 1<<(FILWIDTH_PIN - 8);
#endif
#endif
#if defined(FILWIDTH_PIN) && (FILWIDTH_PIN > -1)
#if FILWIDTH_PIN < 8
DIDR0 |= 1<<FILWIDTH_PIN;
#else
DIDR2 |= 1<<(FILWIDTH_PIN - 8);
#endif
#endif
#endif
// Use timer0 for temperature measurement
@ -1005,6 +1038,28 @@ void tp_init()
}
#endif //MAXTEMP 2
#if (EXTRUDERS > 3) && defined(HEATER_3_MINTEMP)
minttemp[3] = HEATER_3_MINTEMP;
while(analog2temp(minttemp_raw[3], 3) < HEATER_3_MINTEMP) {
#if HEATER_3_RAW_LO_TEMP < HEATER_3_RAW_HI_TEMP
minttemp_raw[3] += OVERSAMPLENR;
#else
minttemp_raw[3] -= OVERSAMPLENR;
#endif
}
#endif //MINTEMP 3
#if (EXTRUDERS > 3) && defined(HEATER_3_MAXTEMP)
maxttemp[3] = HEATER_3_MAXTEMP;
while(analog2temp(maxttemp_raw[3], 3) > HEATER_3_MAXTEMP) {
#if HEATER_3_RAW_LO_TEMP < HEATER_3_RAW_HI_TEMP
maxttemp_raw[3] -= OVERSAMPLENR;
#else
maxttemp_raw[3] += OVERSAMPLENR;
#endif
}
#endif // MAXTEMP 3
#ifdef BED_MINTEMP
/* No bed MINTEMP error implemented?!? */ /*
while(analog2tempBed(bed_minttemp_raw) < BED_MINTEMP) {
@ -1093,6 +1148,7 @@ void thermal_runaway_protection(int *state, unsigned long *timer, float temperat
disable_e0();
disable_e1();
disable_e2();
disable_e3();
manage_heater();
lcd_update();
}
@ -1131,6 +1187,15 @@ void disable_heater()
#endif
#endif
#if defined(TEMP_3_PIN) && TEMP_3_PIN > -1 && EXTRUDERS > 3
target_temperature[3]=0;
soft_pwm[3]=0;
#if defined(HEATER_3_PIN) && HEATER_3_PIN > -1
WRITE(HEATER_3_PIN,LOW);
#endif
#endif
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
target_temperature_bed=0;
soft_pwm_bed=0;
@ -1246,8 +1311,9 @@ ISR(TIMER0_COMPB_vect)
static unsigned long raw_temp_0_value = 0;
static unsigned long raw_temp_1_value = 0;
static unsigned long raw_temp_2_value = 0;
static unsigned long raw_temp_3_value = 0;
static unsigned long raw_temp_bed_value = 0;
static unsigned char temp_state = 10;
static unsigned char temp_state = 12;
static unsigned char pwm_count = (1 << SOFT_PWM_SCALE);
static unsigned char soft_pwm_0;
#ifdef SLOW_PWM_HEATERS
@ -1255,6 +1321,7 @@ ISR(TIMER0_COMPB_vect)
static unsigned char state_heater_0 = 0;
static unsigned char state_timer_heater_0 = 0;
#endif
#if (EXTRUDERS > 1) || defined(HEATERS_PARALLEL)
static unsigned char soft_pwm_1;
#ifdef SLOW_PWM_HEATERS
@ -1269,6 +1336,14 @@ ISR(TIMER0_COMPB_vect)
static unsigned char state_timer_heater_2 = 0;
#endif
#endif
#if EXTRUDERS > 3
static unsigned char soft_pwm_3;
#ifdef SLOW_PWM_HEATERS
static unsigned char state_heater_3 = 0;
static unsigned char state_timer_heater_3 = 0;
#endif
#endif
#if HEATER_BED_PIN > -1
static unsigned char soft_pwm_b;
#ifdef SLOW_PWM_HEATERS
@ -1302,6 +1377,12 @@ ISR(TIMER0_COMPB_vect)
soft_pwm_2 = soft_pwm[2];
if(soft_pwm_2 > 0) WRITE(HEATER_2_PIN,1); else WRITE(HEATER_2_PIN,0);
#endif
#if EXTRUDERS > 3
soft_pwm_3 = soft_pwm[3];
if(soft_pwm_3 > 0) WRITE(HEATER_3_PIN,1); else WRITE(HEATER_3_PIN,0);
#endif
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
soft_pwm_b = soft_pwm_bed;
if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1); else WRITE(HEATER_BED_PIN,0);
@ -1317,12 +1398,17 @@ ISR(TIMER0_COMPB_vect)
WRITE(HEATER_1_PIN,0);
#endif
}
#if EXTRUDERS > 1
if(soft_pwm_1 < pwm_count) WRITE(HEATER_1_PIN,0);
#endif
#if EXTRUDERS > 2
if(soft_pwm_2 < pwm_count) WRITE(HEATER_2_PIN,0);
#endif
#if EXTRUDERS > 3
if(soft_pwm_3 < pwm_count) WRITE(HEATER_3_PIN,0);
#endif
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
if(soft_pwm_b < pwm_count) WRITE(HEATER_BED_PIN,0);
#endif
@ -1425,6 +1511,32 @@ ISR(TIMER0_COMPB_vect)
}
#endif
#if EXTRUDERS > 3
// EXTRUDER 3
soft_pwm_3 = soft_pwm[3];
if (soft_pwm_3 > 0) {
// turn ON heather only if the minimum time is up
if (state_timer_heater_3 == 0) {
// if change state set timer
if (state_heater_3 == 0) {
state_timer_heater_3 = MIN_STATE_TIME;
}
state_heater_3 = 1;
WRITE(HEATER_3_PIN, 1);
}
} else {
// turn OFF heather only if the minimum time is up
if (state_timer_heater_3 == 0) {
// if change state set timer
if (state_heater_3 == 1) {
state_timer_heater_3 = MIN_STATE_TIME;
}
state_heater_3 = 0;
WRITE(HEATER_3_PIN, 0);
}
}
#endif
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
// BED
soft_pwm_b = soft_pwm_bed;
@ -1498,6 +1610,21 @@ ISR(TIMER0_COMPB_vect)
}
#endif
#if EXTRUDERS > 3
// EXTRUDER 3
if (soft_pwm_3 < slow_pwm_count) {
// turn OFF heather only if the minimum time is up
if (state_timer_heater_3 == 0) {
// if change state set timer
if (state_heater_3 == 1) {
state_timer_heater_3 = MIN_STATE_TIME;
}
state_heater_3 = 0;
WRITE(HEATER_3_PIN, 0);
}
}
#endif
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
// BED
if (soft_pwm_b < slow_pwm_count) {
@ -1546,6 +1673,12 @@ ISR(TIMER0_COMPB_vect)
state_timer_heater_2--;
#endif
#if EXTRUDERS > 3
// Extruder 3
if (state_timer_heater_3 > 0)
state_timer_heater_3--;
#endif
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
// Bed
if (state_timer_heater_b > 0)
@ -1630,10 +1763,28 @@ ISR(TIMER0_COMPB_vect)
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
raw_temp_2_value += ADC;
#endif
temp_state = 8;//change so that Filament Width is also measured
temp_state = 8;
break;
case 8: //Prepare FILWIDTH
case 8: // Prepare TEMP_3
#if defined(TEMP_3_PIN) && (TEMP_3_PIN > -1)
#if TEMP_3_PIN > 7
ADCSRB = 1<<MUX5;
#else
ADCSRB = 0;
#endif
ADMUX = ((1 << REFS0) | (TEMP_3_PIN & 0x07));
ADCSRA |= 1<<ADSC; // Start conversion
#endif
lcd_buttons_update();
temp_state = 9;
break;
case 9: // Measure TEMP_3
#if defined(TEMP_3_PIN) && (TEMP_3_PIN > -1)
raw_temp_3_value += ADC;
#endif
temp_state = 10; //change so that Filament Width is also measured
break;
case 10: //Prepare FILWIDTH
#if defined(FILWIDTH_PIN) && (FILWIDTH_PIN> -1)
#if FILWIDTH_PIN>7
ADCSRB = 1<<MUX5;
@ -1644,9 +1795,9 @@ ISR(TIMER0_COMPB_vect)
ADCSRA |= 1<<ADSC; // Start conversion
#endif
lcd_buttons_update();
temp_state = 9;
temp_state = 11;
break;
case 9: //Measure FILWIDTH
case 11: //Measure FILWIDTH
#if defined(FILWIDTH_PIN) &&(FILWIDTH_PIN > -1)
//raw_filwidth_value += ADC; //remove to use an IIR filter approach
if(ADC>102) //check that ADC is reading a voltage > 0.5 volts, otherwise don't take in the data.
@ -1662,7 +1813,7 @@ ISR(TIMER0_COMPB_vect)
break;
case 10: //Startup, delay initial temp reading a tiny bit so the hardware can settle.
case 12: //Startup, delay initial temp reading a tiny bit so the hardware can settle.
temp_state = 0;
break;
// default:
@ -1686,6 +1837,9 @@ ISR(TIMER0_COMPB_vect)
#endif
#if EXTRUDERS > 2
current_temperature_raw[2] = raw_temp_2_value;
#endif
#if EXTRUDERS > 3
current_temperature_raw[3] = raw_temp_3_value;
#endif
current_temperature_bed_raw = raw_temp_bed_value;
}
@ -1701,6 +1855,7 @@ ISR(TIMER0_COMPB_vect)
raw_temp_0_value = 0;
raw_temp_1_value = 0;
raw_temp_2_value = 0;
raw_temp_3_value = 0;
raw_temp_bed_value = 0;
#if HEATER_0_RAW_LO_TEMP > HEATER_0_RAW_HI_TEMP
@ -1721,6 +1876,8 @@ ISR(TIMER0_COMPB_vect)
min_temp_error(0);
#endif
}
#if EXTRUDERS > 1
#if HEATER_1_RAW_LO_TEMP > HEATER_1_RAW_HI_TEMP
if(current_temperature_raw[1] <= maxttemp_raw[1]) {
@ -1753,6 +1910,23 @@ ISR(TIMER0_COMPB_vect)
min_temp_error(2);
}
#endif
#if EXTRUDERS > 3
#if HEATER_3_RAW_LO_TEMP > HEATER_3_RAW_HI_TEMP
if(current_temperature_raw[3] <= maxttemp_raw[3]) {
#else
if(current_temperature_raw[3] >= maxttemp_raw[3]) {
#endif
max_temp_error(3);
}
#if HEATER_3_RAW_LO_TEMP > HEATER_3_RAW_HI_TEMP
if(current_temperature_raw[3] >= minttemp_raw[3]) {
#else
if(current_temperature_raw[3] <= minttemp_raw[3]) {
#endif
min_temp_error(3);
}
#endif
/* No bed MINTEMP error? */
#if defined(BED_MAXTEMP) && (TEMP_SENSOR_BED != 0)
@ -1812,5 +1986,3 @@ float unscalePID_d(float d)
}
#endif //PIDTEMP

@ -159,6 +159,15 @@ FORCE_INLINE bool isCoolingBed() {
#define setTargetHotend2(_celsius) do{}while(0)
#endif
#if EXTRUDERS > 3
#define degHotend3() degHotend(3)
#define degTargetHotend3() degTargetHotend(3)
#define setTargetHotend3(_celsius) setTargetHotend((_celsius), 3)
#define isHeatingHotend3() isHeatingHotend(3)
#define isCoolingHotend3() isCoolingHotend(3)
#else
#define setTargetHotend3(_celsius) do{}while(0)
#endif
#if EXTRUDERS > 4
#error Invalid number of extruders
#endif
@ -171,24 +180,24 @@ void updatePID();
#if defined (THERMAL_RUNAWAY_PROTECTION_PERIOD) && THERMAL_RUNAWAY_PROTECTION_PERIOD > 0
void thermal_runaway_protection(int *state, unsigned long *timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc);
static int thermal_runaway_state_machine[3]; // = {0,0,0};
static unsigned long thermal_runaway_timer[3]; // = {0,0,0};
static int thermal_runaway_state_machine[4]; // = {0,0,0,0};
static unsigned long thermal_runaway_timer[4]; // = {0,0,0,0};
static bool thermal_runaway = false;
#if TEMP_SENSOR_BED != 0
static int thermal_runaway_bed_state_machine;
static unsigned long thermal_runaway_bed_timer;
#endif
#if TEMP_SENSOR_BED != 0
static int thermal_runaway_bed_state_machine;
static unsigned long thermal_runaway_bed_timer;
#endif
#endif
FORCE_INLINE void autotempShutdown(){
#ifdef AUTOTEMP
if(autotemp_enabled)
{
autotemp_enabled=false;
if(degTargetHotend(active_extruder)>autotemp_min)
setTargetHotend(0,active_extruder);
}
#endif
#ifdef AUTOTEMP
if(autotemp_enabled)
{
autotemp_enabled=false;
if(degTargetHotend(active_extruder)>autotemp_min)
setTargetHotend(0,active_extruder);
}
#endif
}
void PID_autotune(float temp, int extruder, int ncycles);
@ -197,4 +206,3 @@ void setExtruderAutoFanState(int pin, bool state);
void checkExtruderAutoFans();
#endif

@ -5,7 +5,7 @@
#define OVERSAMPLENR 16
#if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1) || (THERMISTORHEATER_2 == 1) || (THERMISTORBED == 1) //100k bed thermistor
#if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1) || (THERMISTORHEATER_2 == 1) || (THERMISTORHEATER_3 == 1) || (THERMISTORBED == 1) //100k bed thermistor
const short temptable_1[][2] PROGMEM = {
{ 23*OVERSAMPLENR , 300 },
@ -71,7 +71,7 @@ const short temptable_1[][2] PROGMEM = {
{ 1008*OVERSAMPLENR , 0 } //safety
};
#endif
#if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORBED == 2) //200k bed thermistor
#if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORHEATER_3 == 2) || (THERMISTORBED == 2) //200k bed thermistor
const short temptable_2[][2] PROGMEM = {
//200k ATC Semitec 204GT-2
//Verified by linagee. Source: http://shop.arcol.hu/static/datasheets/thermistors.pdf
@ -111,7 +111,7 @@ const short temptable_2[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORBED == 3) //mendel-parts
#if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORHEATER_3 == 3) || (THERMISTORBED == 3) //mendel-parts
const short temptable_3[][2] PROGMEM = {
{1*OVERSAMPLENR,864},
{21*OVERSAMPLENR,300},
@ -144,7 +144,7 @@ const short temptable_3[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORBED == 4) //10k thermistor
#if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORHEATER_3 == 4) || (THERMISTORBED == 4) //10k thermistor
const short temptable_4[][2] PROGMEM = {
{1*OVERSAMPLENR, 430},
{54*OVERSAMPLENR, 137},
@ -169,7 +169,7 @@ const short temptable_4[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORHEATER_2 == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2)
#if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORHEATER_2 == 5) || (THERMISTORHEATER_3 == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2)
const short temptable_5[][2] PROGMEM = {
// ATC Semitec 104GT-2 (Used in ParCan)
// Verified by linagee. Source: http://shop.arcol.hu/static/datasheets/thermistors.pdf
@ -209,7 +209,7 @@ const short temptable_5[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORHEATER_2 == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor
#if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORHEATER_2 == 6) || (THERMISTORHEATER_3 == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor
const short temptable_6[][2] PROGMEM = {
{1*OVERSAMPLENR, 350},
{28*OVERSAMPLENR, 250}, //top rating 250C
@ -252,7 +252,7 @@ const short temptable_6[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORHEATER_2 == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01
#if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORHEATER_2 == 7) || (THERMISTORHEATER_3 == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01
const short temptable_7[][2] PROGMEM = {
{1*OVERSAMPLENR, 941},
{19*OVERSAMPLENR, 362},
@ -315,7 +315,7 @@ const short temptable_7[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 71) || (THERMISTORHEATER_1 == 71) || (THERMISTORHEATER_2 == 71) || (THERMISTORBED == 71) // 100k Honeywell 135-104LAF-J01
#if (THERMISTORHEATER_0 == 71) || (THERMISTORHEATER_1 == 71) || (THERMISTORHEATER_2 == 71) || (THERMISTORHEATER_3 == 71) || (THERMISTORBED == 71) // 100k Honeywell 135-104LAF-J01
// R0 = 100000 Ohm
// T0 = 25 °C
// Beta = 3974
@ -466,7 +466,7 @@ const short temptable_71[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 8) || (THERMISTORHEATER_1 == 8) || (THERMISTORHEATER_2 == 8) || (THERMISTORBED == 8)
#if (THERMISTORHEATER_0 == 8) || (THERMISTORHEATER_1 == 8) || (THERMISTORHEATER_2 == 8) || (THERMISTORHEATER_3 == 8) || (THERMISTORBED == 8)
// 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
const short temptable_8[][2] PROGMEM = {
{1*OVERSAMPLENR, 704},
@ -491,7 +491,7 @@ const short temptable_8[][2] PROGMEM = {
{1008*OVERSAMPLENR, 0}
};
#endif
#if (THERMISTORHEATER_0 == 9) || (THERMISTORHEATER_1 == 9) || (THERMISTORHEATER_2 == 9) || (THERMISTORBED == 9)
#if (THERMISTORHEATER_0 == 9) || (THERMISTORHEATER_1 == 9) || (THERMISTORHEATER_2 == 9) || (THERMISTORHEATER_3 == 9) || (THERMISTORBED == 9)
// 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
const short temptable_9[][2] PROGMEM = {
{1*OVERSAMPLENR, 936},
@ -527,7 +527,7 @@ const short temptable_9[][2] PROGMEM = {
{1016*OVERSAMPLENR, 0}
};
#endif
#if (THERMISTORHEATER_0 == 10) || (THERMISTORHEATER_1 == 10) || (THERMISTORHEATER_2 == 10) || (THERMISTORBED == 10)
#if (THERMISTORHEATER_0 == 10) || (THERMISTORHEATER_1 == 10) || (THERMISTORHEATER_2 == 10) || (THERMISTORHEATER_3 == 10) || (THERMISTORBED == 10)
// 100k RS thermistor 198-961 (4.7k pullup)
const short temptable_10[][2] PROGMEM = {
{1*OVERSAMPLENR, 929},
@ -564,7 +564,7 @@ const short temptable_10[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 11) || (THERMISTORHEATER_1 == 11) || (THERMISTORHEATER_2 == 11) || (THERMISTORBED == 11)
#if (THERMISTORHEATER_0 == 11) || (THERMISTORHEATER_1 == 11) || (THERMISTORHEATER_2 == 11) || (THERMISTORHEATER_3 == 11) || (THERMISTORBED == 11)
// QU-BD silicone bed QWG-104F-3950 thermistor
const short temptable_11[][2] PROGMEM = {
@ -621,7 +621,7 @@ const short temptable_11[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 13) || (THERMISTORHEATER_1 == 13) || (THERMISTORHEATER_2 == 13) || (THERMISTORBED == 13)
#if (THERMISTORHEATER_0 == 13) || (THERMISTORHEATER_1 == 13) || (THERMISTORHEATER_2 == 13) || (THERMISTORHEATER_3 == 13) || (THERMISTORBED == 13)
// Hisens thermistor B25/50 =3950 +/-1%
const short temptable_13[][2] PROGMEM = {
@ -705,6 +705,10 @@ This does not match the normal thermistor behaviour so we need to set the follow
# define HEATER_2_RAW_HI_TEMP 16383
# define HEATER_2_RAW_LO_TEMP 0
#endif
#if (THERMISTORHEATER_3 == 20)
# define HEATER_3_RAW_HI_TEMP 16383
# define HEATER_3_RAW_LO_TEMP 0
#endif
#if (THERMISTORBED == 20)
# define HEATER_BED_RAW_HI_TEMP 16383
# define HEATER_BED_RAW_LO_TEMP 0
@ -762,7 +766,7 @@ const short temptable_20[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 51) || (THERMISTORHEATER_1 == 51) || (THERMISTORHEATER_2 == 51) || (THERMISTORBED == 51)
#if (THERMISTORHEATER_0 == 51) || (THERMISTORHEATER_1 == 51) || (THERMISTORHEATER_2 == 51) || (THERMISTORHEATER_3 == 51) || (THERMISTORBED == 51)
// 100k EPCOS (WITH 1kohm RESISTOR FOR PULLUP, R9 ON SANGUINOLOLU! NOT FOR 4.7kohm PULLUP! THIS IS NOT NORMAL!)
// Verified by linagee.
// Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance
@ -824,7 +828,7 @@ const short temptable_51[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 52) || (THERMISTORHEATER_1 == 52) || (THERMISTORHEATER_2 == 52) || (THERMISTORBED == 52)
#if (THERMISTORHEATER_0 == 52) || (THERMISTORHEATER_1 == 52) || (THERMISTORHEATER_2 == 52) || (THERMISTORHEATER_3 == 52) || (THERMISTORBED == 52)
// 200k ATC Semitec 204GT-2 (WITH 1kohm RESISTOR FOR PULLUP, R9 ON SANGUINOLOLU! NOT FOR 4.7kohm PULLUP! THIS IS NOT NORMAL!)
// Verified by linagee. Source: http://shop.arcol.hu/static/datasheets/thermistors.pdf
// Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance
@ -865,7 +869,7 @@ const short temptable_52[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 55) || (THERMISTORHEATER_1 == 55) || (THERMISTORHEATER_2 == 55) || (THERMISTORBED == 55)
#if (THERMISTORHEATER_0 == 55) || (THERMISTORHEATER_1 == 55) || (THERMISTORHEATER_2 == 55) || (THERMISTORHEATER_3 == 55) || (THERMISTORBED == 55)
// 100k ATC Semitec 104GT-2 (Used on ParCan) (WITH 1kohm RESISTOR FOR PULLUP, R9 ON SANGUINOLOLU! NOT FOR 4.7kohm PULLUP! THIS IS NOT NORMAL!)
// Verified by linagee. Source: http://shop.arcol.hu/static/datasheets/thermistors.pdf
// Calculated using 1kohm pullup, voltage divider math, and manufacturer provided temp/resistance
@ -906,7 +910,7 @@ const short temptable_55[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 60) || (THERMISTORHEATER_1 == 60) || (THERMISTORHEATER_2 == 60) || (THERMISTORBED == 60) // Maker's Tool Works Kapton Bed Thermister
#if (THERMISTORHEATER_0 == 60) || (THERMISTORHEATER_1 == 60) || (THERMISTORHEATER_2 == 60) || (THERMISTORHEATER_3 == 60) || (THERMISTORBED == 60) // Maker's Tool Works Kapton Bed Thermister
// ./createTemperatureLookup.py --r0=100000 --t0=25 --r1=0 --r2=4700 --beta=3950
// r0: 100000
// t0: 25
@ -1037,7 +1041,7 @@ const short temptable_12[][2] PROGMEM = {
#define PtAdVal(T,R0,Rup) (short)(1024/(Rup/PtRt(T,R0)+1))
#define PtLine(T,R0,Rup) { PtAdVal(T,R0,Rup)*OVERSAMPLENR, T },
#if (THERMISTORHEATER_0 == 110) || (THERMISTORHEATER_1 == 110) || (THERMISTORHEATER_2 == 110) || (THERMISTORBED == 110) // Pt100 with 1k0 pullup
#if (THERMISTORHEATER_0 == 110) || (THERMISTORHEATER_1 == 110) || (THERMISTORHEATER_2 == 110) || (THERMISTORHEATER_3 == 110) || (THERMISTORBED == 110) // Pt100 with 1k0 pullup
const short temptable_110[][2] PROGMEM = {
// only few values are needed as the curve is very flat
PtLine(0,100,1000)
@ -1049,7 +1053,7 @@ const short temptable_110[][2] PROGMEM = {
PtLine(300,100,1000)
};
#endif
#if (THERMISTORHEATER_0 == 147) || (THERMISTORHEATER_1 == 147) || (THERMISTORHEATER_2 == 147) || (THERMISTORBED == 147) // Pt100 with 4k7 pullup
#if (THERMISTORHEATER_0 == 147) || (THERMISTORHEATER_1 == 147) || (THERMISTORHEATER_2 == 147) || (THERMISTORHEATER_3 == 147) || (THERMISTORBED == 147) // Pt100 with 4k7 pullup
const short temptable_147[][2] PROGMEM = {
// only few values are needed as the curve is very flat
PtLine(0,100,4700)
@ -1061,7 +1065,7 @@ const short temptable_147[][2] PROGMEM = {
PtLine(300,100,4700)
};
#endif
#if (THERMISTORHEATER_0 == 1010) || (THERMISTORHEATER_1 == 1010) || (THERMISTORHEATER_2 == 1010) || (THERMISTORBED == 1010) // Pt1000 with 1k0 pullup
#if (THERMISTORHEATER_0 == 1010) || (THERMISTORHEATER_1 == 1010) || (THERMISTORHEATER_2 == 1010) || (THERMISTORHEATER_3 == 1010) || (THERMISTORBED == 1010) // Pt1000 with 1k0 pullup
const short temptable_1010[][2] PROGMEM = {
PtLine(0,1000,1000)
PtLine(25,1000,1000)
@ -1078,7 +1082,7 @@ const short temptable_1010[][2] PROGMEM = {
PtLine(300,1000,1000)
};
#endif
#if (THERMISTORHEATER_0 == 1047) || (THERMISTORHEATER_1 == 1047) || (THERMISTORHEATER_2 == 1047) || (THERMISTORBED == 1047) // Pt1000 with 4k7 pullup
#if (THERMISTORHEATER_0 == 1047) || (THERMISTORHEATER_1 == 1047) || (THERMISTORHEATER_2 == 1047) || (THERMISTORHEATER_3 == 1047) || (THERMISTORBED == 1047) // Pt1000 with 4k7 pullup
const short temptable_1047[][2] PROGMEM = {
// only few values are needed as the curve is very flat
PtLine(0,1000,4700)
@ -1163,6 +1167,29 @@ const short temptable_1047[][2] PROGMEM = {
# endif
#endif
#ifdef THERMISTORHEATER_3
# define HEATER_3_TEMPTABLE TT_NAME(THERMISTORHEATER_3)
# define HEATER_3_TEMPTABLE_LEN (sizeof(HEATER_3_TEMPTABLE)/sizeof(*HEATER_3_TEMPTABLE))
#else
# ifdef HEATER_3_USES_THERMISTOR
# error No heater 3 thermistor table specified
# else // HEATER_3_USES_THERMISTOR
# define HEATER_3_TEMPTABLE NULL
# define HEATER_3_TEMPTABLE_LEN 0
# endif // HEATER_3_USES_THERMISTOR
#endif
//Set the high and low raw values for the heater, this indicates which raw value is a high or low temperature
#ifndef HEATER_3_RAW_HI_TEMP
# ifdef HEATER_3_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
# define HEATER_3_RAW_HI_TEMP 0
# define HEATER_3_RAW_LO_TEMP 16383
# else //In case of an thermocouple the highest temperature results in the highest ADC value
# define HEATER_3_RAW_HI_TEMP 16383
# define HEATER_3_RAW_LO_TEMP 0
# endif
#endif
#ifdef THERMISTORBED
# define BEDTEMPTABLE TT_NAME(THERMISTORBED)
# define BEDTEMPTABLE_LEN (sizeof(BEDTEMPTABLE)/sizeof(*BEDTEMPTABLE))

@ -431,6 +431,11 @@ static void lcd_tune_menu()
#if TEMP_SENSOR_2 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE2, &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_3 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE3, &target_temperature[3], 0, HEATER_3_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
#endif
@ -443,6 +448,10 @@ static void lcd_tune_menu()
#if TEMP_SENSOR_2 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW2, &extruder_multiply[2], 10, 999);
#endif
#if TEMP_SENSOR_3 != 0
MENU_ITEM_EDIT(int3, MSG_FLOW3, &extruder_multiply[3], 10, 999);
#endif
#ifdef BABYSTEPPING
#ifdef BABYSTEP_XY
@ -515,23 +524,46 @@ void lcd_preheat_abs2()
}
#endif //3 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 //more than one extruder present
void lcd_preheat_pla012()
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
void lcd_preheat_pla3()
{
setTargetHotend3(plaPreheatHotendTemp);
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_abs3()
{
setTargetHotend3(absPreheatHotendTemp);
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //more than one extruder present
void lcd_preheat_pla0123()
{
setTargetHotend0(plaPreheatHotendTemp);
setTargetHotend1(plaPreheatHotendTemp);
setTargetHotend2(plaPreheatHotendTemp);
setTargetHotend3(plaPreheatHotendTemp);
setTargetBed(plaPreheatHPBTemp);
fanSpeed = plaPreheatFanSpeed;
lcd_return_to_status();
setWatch(); // heater sanity check timer
}
void lcd_preheat_abs012()
void lcd_preheat_abs0123()
{
setTargetHotend0(absPreheatHotendTemp);
setTargetHotend1(absPreheatHotendTemp);
setTargetHotend2(absPreheatHotendTemp);
setTargetHotend3(absPreheatHotendTemp);
setTargetBed(absPreheatHPBTemp);
fanSpeed = absPreheatFanSpeed;
lcd_return_to_status();
@ -557,42 +589,49 @@ void lcd_preheat_abs_bedonly()
static void lcd_preheat_pla_menu()
{
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
MENU_ITEM(function, MSG_PREHEAT_PLA0, lcd_preheat_pla0);
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
MENU_ITEM(function, MSG_PREHEAT_PLA0, lcd_preheat_pla0);
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA1, lcd_preheat_pla1);
MENU_ITEM(function, MSG_PREHEAT_PLA1, lcd_preheat_pla1);
#endif //2 extruder preheat
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA2, lcd_preheat_pla2);
MENU_ITEM(function, MSG_PREHEAT_PLA2, lcd_preheat_pla2);
#endif //3 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA012, lcd_preheat_pla012);
#endif //2 extruder preheat
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA3, lcd_preheat_pla3);
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_PLA0123, lcd_preheat_pla0123);
#endif //all extruder preheat
#if TEMP_SENSOR_BED != 0
MENU_ITEM(function, MSG_PREHEAT_PLA_BEDONLY, lcd_preheat_pla_bedonly);
MENU_ITEM(function, MSG_PREHEAT_PLA_BEDONLY, lcd_preheat_pla_bedonly);
#endif
END_MENU();
END_MENU();
}
static void lcd_preheat_abs_menu()
{
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
MENU_ITEM(function, MSG_PREHEAT_ABS0, lcd_preheat_abs0);
START_MENU();
MENU_ITEM(back, MSG_PREPARE, lcd_prepare_menu);
MENU_ITEM(function, MSG_PREHEAT_ABS0, lcd_preheat_abs0);
#if TEMP_SENSOR_1 != 0 //2 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS1, lcd_preheat_abs1);
MENU_ITEM(function, MSG_PREHEAT_ABS1, lcd_preheat_abs1);
#endif //2 extruder preheat
#if TEMP_SENSOR_2 != 0 //3 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS2, lcd_preheat_abs2);
MENU_ITEM(function, MSG_PREHEAT_ABS2, lcd_preheat_abs2);
#endif //3 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS012, lcd_preheat_abs012);
#endif //2 extruder preheat
#if TEMP_SENSOR_3 != 0 //4 extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS3, lcd_preheat_abs3);
#endif //4 extruder preheat
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 //all extruder preheat
MENU_ITEM(function, MSG_PREHEAT_ABS0123, lcd_preheat_abs0123);
#endif //all extruder preheat
#if TEMP_SENSOR_BED != 0
MENU_ITEM(function, MSG_PREHEAT_ABS_BEDONLY, lcd_preheat_abs_bedonly);
MENU_ITEM(function, MSG_PREHEAT_ABS_BEDONLY, lcd_preheat_abs_bedonly);
#endif
END_MENU();
END_MENU();
}
void lcd_cooldown()
@ -600,6 +639,7 @@ void lcd_cooldown()
setTargetHotend0(0);
setTargetHotend1(0);
setTargetHotend2(0);
setTargetHotend3(0);
setTargetBed(0);
fanSpeed = 0;
lcd_return_to_status();
@ -747,7 +787,7 @@ static void lcd_control_menu()
MENU_ITEM(back, MSG_MAIN, lcd_main_menu);
MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu);
MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu);
MENU_ITEM(submenu, MSG_VOLUMETRIC, lcd_control_volumetric_menu);
MENU_ITEM(submenu, MSG_VOLUMETRIC, lcd_control_volumetric_menu);
#ifdef DOGLCD
// MENU_ITEM_EDIT(int3, MSG_CONTRAST, &lcd_contrast, 0, 63);
@ -766,26 +806,29 @@ static void lcd_control_menu()
static void lcd_control_temperature_menu()
{
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
START_MENU();
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
#if TEMP_SENSOR_0 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_1 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_NOZZLE1, &target_temperature[1], 0, HEATER_1_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_2 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE2, &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_NOZZLE2, &target_temperature[2], 0, HEATER_2_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_3 != 0
MENU_ITEM_EDIT(int3, MSG_NOZZLE3, &target_temperature[3], 0, HEATER_3_MAXTEMP - 15);
#endif
#if TEMP_SENSOR_BED != 0
MENU_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
MENU_ITEM_EDIT(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15);
#endif
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
#if defined AUTOTEMP && (TEMP_SENSOR_0 != 0)
MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &autotemp_enabled);
MENU_ITEM_EDIT(float3, MSG_MIN, &autotemp_min, 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(float3, MSG_MAX, &autotemp_max, 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(float32, MSG_FACTOR, &autotemp_factor, 0.0, 1.0);
MENU_ITEM_EDIT(bool, MSG_AUTOTEMP, &autotemp_enabled);
MENU_ITEM_EDIT(float3, MSG_MIN, &autotemp_min, 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(float3, MSG_MAX, &autotemp_max, 0, HEATER_0_MAXTEMP - 15);
MENU_ITEM_EDIT(float32, MSG_FACTOR, &autotemp_factor, 0.0, 1.0);
#endif
#ifdef PIDTEMP
// set up temp variables - undo the default scaling
@ -916,13 +959,15 @@ static void lcd_control_volumetric_menu()
MENU_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_SIZE_EXTRUDER_1, &filament_size[1], DEFAULT_NOMINAL_FILAMENT_DIA - .5, DEFAULT_NOMINAL_FILAMENT_DIA + .5, calculate_volumetric_multipliers);
#if EXTRUDERS > 2
MENU_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_SIZE_EXTRUDER_2, &filament_size[2], DEFAULT_NOMINAL_FILAMENT_DIA - .5, DEFAULT_NOMINAL_FILAMENT_DIA + .5, calculate_volumetric_multipliers);
#endif
#endif
#if EXTRUDERS > 3
MENU_ITEM_EDIT_CALLBACK(float43, MSG_FILAMENT_SIZE_EXTRUDER_3, &filament_size[3], DEFAULT_NOMINAL_FILAMENT_DIA - .5, DEFAULT_NOMINAL_FILAMENT_DIA + .5, calculate_volumetric_multipliers);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
}
END_MENU();
}
#ifdef DOGLCD
static void lcd_set_contrast()
{
@ -950,19 +995,18 @@ static void lcd_control_retract_menu()
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
MENU_ITEM_EDIT(bool, MSG_AUTORETRACT, &autoretract_enabled);
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT, &retract_length, 0, 100);
#if EXTRUDERS > 1
#if EXTRUDERS > 1
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_SWAP, &retract_length_swap, 0, 100);
#endif
MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACTF, &retract_feedrate, 1, 999);
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_ZLIFT, &retract_zlift, 0, 999);
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER, &retract_recover_length, 0, 100);
#if EXTRUDERS > 1
#if EXTRUDERS > 1
MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER_SWAP, &retract_recover_length_swap, 0, 100);
#endif
MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACT_RECOVERF, &retract_recover_feedrate, 1, 999);
END_MENU();
}
#endif //FWRETRACT
#if SDCARDDETECT == -1

@ -46,9 +46,9 @@
extern bool cancel_heatup;
#ifdef FILAMENT_LCD_DISPLAY
extern unsigned long message_millis;
#endif
#ifdef FILAMENT_LCD_DISPLAY
extern unsigned long message_millis;
#endif
void lcd_buzz(long duration,uint16_t freq);
bool lcd_clicked();

Loading…
Cancel
Save