Commit 586fed8a authored by Stefy Lanza (nextime / spora )'s avatar Stefy Lanza (nextime / spora )

Merge branch 'dev'

parents 32b99d79 252fa2d0
Pipeline #53 skipped
......@@ -8,10 +8,10 @@
* G3 - CCW ARC
* G4 - Dwell S[seconds] or P[milliseconds], delay in Second or Millisecond
* G5 - Bezier curve - from http://forums.reprap.org/read.php?147,93577
* G7 - execute raster (base64) line (LASER)
* G7 - Laser raster base64
* G10 - retract filament according to settings of M207
* G11 - retract recover filament according to settings of M208
* G28 - X0 Y0 Z0 Home all Axis. G28 M for bed manual setting with LCD.
* G28 - X Y Z Home all Axis. M for bed manual setting with LCD. B return to back point
* G29 - Detailed Z-Probe, probes the bed at 3 points or grid. You must be at the home position for this to work correctly.
G29 Fyyy Lxxx Rxxx Byyy for customer grid.
* G30 - Single Z Probe, probes bed at current XY location. Bed Probe and Delta geometry Autocalibration G30 A
......@@ -47,7 +47,8 @@
* M32 - Make directory
* M35 - Upload Firmware to Nextion from SD
* M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used.
* M49 - Z probe repetability test
* M48 - Measure Z_Probe repeatability. M48 [P # of points] [X position] [Y position] [V_erboseness #] [E_ngage Probe] [L # of legs of travel]
* M70 - Power consumption sensor calibration
* M80 - Turn on Power Supply
* M81 - Turn off Power, including Power Supply, if possible
* M82 - Set E codes absolute (default)
......@@ -60,34 +61,40 @@
* M98 - Print Hysteresis value
* M99 - Set Hysteresis parameter M99 X<in mm> Y<in mm> Z<in mm> E<in mm>
* M100 - Watch Free Memory (For Debugging Only)
* M104 - Set extruder target temp
* M104 - Set hotend target temp
* M105 - Read current temp
* M106 - Fan on
* M107 - Fan off
* M109 - S[xxx] Wait for extruder current temp to reach target temp. Waits only when heating
- R[xxx] Wait for extruder current temp to reach target temp. Waits when heating and cooling
* M111 - Debug Dryrun Repetier
* M109 - S[xxx] Wait for hotend current temp to reach target temp. Waits only when heating
- R[xxx] Wait for hotend current temp to reach target temp. Waits when heating and cooling
* M110 - Set the current line number
* M111 - Set debug flags with S<mask>.
* M112 - Emergency stop
* M114 - Output current position to serial port, (V)erbose for user
* M114 - Output current position to serial port
* M115 - Capabilities string
* M117 - display message
* M117 - Display a message on the controller screen
* M119 - Output Endstop status to serial port
* M120 - Disable Endstop
* M121 - Enable Endstop
* M120 - Enable endstop detection
* M121 - Disable endstop detection
* M122 - S<1=true/0=false> Enable or disable check software endstop
* M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
* M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
* M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
* M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
* M140 - Set bed or cooler target temp
* M140 - Set hot bed target temp
* M141 - Set hot chamber target temp
* M142 - Set cooler target temp
* M145 - Set the heatup state H<hotend> B<bed> F<fan speed> for S<material> (0=PLA, 1=ABS)
* M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work.
* M163 - Set a single proportion for a mixing extruder. Requires COLOR_MIXING_EXTRUDER.
* M164 - Save the mix as a virtual extruder. Requires COLOR_MIXING_EXTRUDER and MIXING_VIRTUAL_TOOLS.
* M165 - Set the proportions for a mixing extruder. Use parameters ABCDHI to set the mixing factors. Requires COLOR_MIXING_EXTRUDER.
* M190 - S[xxx] Wait for bed or cooler current temp to reach target temp. Waits only when heating bed or cooling cooler
- R[xxx] Wait for bed or cooler current temp to reach target temp. Waits when heating and cooling
- C parameter select Cooler, omitting it selec bed.
* M190 - S[xxx] Wait for bed current temp to reach target temp. Waits only when heating
- R[xxx] Wait for bed current temp to reach target temp. Waits when heating and cooling
* M191 - Sxxx Wait for chamber current temp to reach target temp. Waits only when heating
* Rxxx Wait for chamber current temp to reach target temp. Waits when heating and cooling
* M192 - Sxxx Wait for cooler current temp to reach target temp. Waits only when heating
* Rxxx Wait for cooler current temp to reach target temp. Waits when heating and cooling
* M200 - D[millimeters]- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
* M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000 Z1000 E0 S1000 E1 S1000 E2 S1000 E3 S1000) in mm/sec^2
* M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E0 S1000 E1 S1000 E2 S1000 E3 S1000) in mm/sec
......@@ -107,7 +114,9 @@
* M301 - Set PID parameters P I and D
* M302 - Allow cold extrudes
* M303 - PID relay autotune S<temperature> sets the target temperature (default target temperature = 150C). H<hotend> C<cycles> U<Apply result>
* M304 - Set bed PID parameters P I and D or Water Cooling if C parameter
* M304 - Set hot bed PID parameters P I and D
* M305 - Set hot chamber PID parameters P I and D
* M306 - Set cooler PID parameters P I and D
* M350 - Set microstepping mode.
* M351 - Toggle MS1 MS2 pins directly.
* M400 - Finish all moves
......@@ -129,12 +138,11 @@
* M595 - Set hotend AD595 offset and gain
* M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
* M605 - Set dual x-carriage movement mode: Smode [ X<duplication x-offset> Rduplication temp offset ]
* M649 - laser set options
* M650 - mUVe peel set peel distance
* M651 - mUVe peel run peel move
* M649 - Set laser options. S<intensity> L<duration> P<ppm> B<set mode> R<raster mm per pulse> F<feedrate>
* M666 - Set z probe offset or Endstop and delta geometry adjustment. M666 L for list command
* M906 - Set motor currents XYZ T0-4 E
* M907 - Set digital trimpot motor current using axis codes.
* M908 - Control digital trimpot directly.
* M928 - Start SD logging (M928 filename.g) - ended by M29
* M997 - NPR2 Color rotate
* M999 - Restart after being stopped by error
### Version 4.2.83
* Add Cooler and Hot Chamber
* Add Laser Beam PWM and raster base64
### Version 4.2.82
* Add DONDOLO_DUAL_MOTOR for DONDOLO bowden and dual extruder
* Add reader TAG width MFRC522
......
......@@ -7,10 +7,9 @@
* - Board type
* - Mechanism type
* - Extruders number
* - Thermistor type
* - Temperature limits
*
* Mechanisms-settings can be found in Configuration_Xxxxxx.h (where Xxxxxx can be: Cartesian - Delta - Core - Scara)
* Temperature settings can be found in Configuration_Temperature.h
* Feature-settings can be found in Configuration_Feature.h
* Pins-settings can be found in "Configuration_Pins.h"
*/
......@@ -116,16 +115,6 @@
//#define PS_DEFAULT_OFF
/*************************************************************************************/
/***********************************************************************
******************************* Cooler ********************************
***********************************************************************
* *
* Uncomment the following line to enable COOLER support *
* *
***********************************************************************/
//#define COOLER
/***********************************************************************
************************** Extruders number ***************************
......@@ -137,128 +126,4 @@
#define DRIVER_EXTRUDERS 1
/***********************************************************************/
/*****************************************************************************************************
************************************** Thermistor type **********************************************
*****************************************************************************************************
* *
* 4.7kohm PULLUP! *
* This is a normal value, if you use a 1k pullup thermistor see below *
* Please choose the one that matches your setup and set to TEMP_SENSOR_. *
* *
* Temperature sensor settings (4.7kohm PULLUP): *
* -2 is thermocouple with MAX6675 (only for sensor 0) *
* -1 is thermocouple with AD595 or AD597 *
* 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 *
* 40 is the 10k Carel NTC015WH01 or ELIWELL SN8T6A1502 (4.7k pullup) *
* 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 *
* *
* 1kohm PULLUP! *
* This is not normal, you would have to have changed out your 4.7k for 1k *
* (but gives greater accuracy and more stable PID) *
* Please choose the one that matches your setup. *
* *
* Temperature sensor settings (1kohm PULLUP): *
* 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) *
* 998 and 999 are Dummy Tables. ALWAYS read 25°C or DUMMY_THERMISTOR_998_VALUE temperature *
* *
*****************************************************************************************************/
#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
#define TEMP_SENSOR_COOLER 0
//These 2 defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Use it for Testing or Development purposes. NEVER for production machine.
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 25
//Show Temperature ADC value
//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
//#define SHOW_TEMP_ADC_VALUES
/*****************************************************************************************************/
/***********************************************************************
************************* Temperature limits ***************************
***********************************************************************/
// Hotend temperature must be close to target for this long before M109 returns success
#define TEMP_RESIDENCY_TIME 10 // (seconds)
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// Bed temperature must be close to target for this long before M190 returns success
#define TEMP_BED_RESIDENCY_TIME 0 // (seconds)
#define TEMP_BED_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_BED_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// Cooler temperature must be close to target for this long before M190 returns success
#define TEMP_COOLER_RESIDENCY_TIME 0 // (seconds)
#define TEMP_COOLER_HYSTERESIS 1 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_COOLER_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// When temperature exceeds max temp, your heater will be switched off.
// When temperature exceeds max temp, your cooler cannot be activaed.
// 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 // (degC)
#define HEATER_1_MAXTEMP 275 // (degC)
#define HEATER_2_MAXTEMP 275 // (degC)
#define HEATER_3_MAXTEMP 275 // (degC)
#define BED_MAXTEMP 150 // (degC)
#define COOLER_MAXTEMP 35 //
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
// or, in case of cooler, it will switched off.
// 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 // (degC)
#define HEATER_1_MINTEMP 5 // (degC)
#define HEATER_2_MINTEMP 5 // (degC)
#define HEATER_3_MINTEMP 5 // (degC)
#define BED_MINTEMP 5 // (degC)
#define COOLER_MINTEMP 10 // (degC)
//Preheat Constants
#define PLA_PREHEAT_HOTEND_TEMP 190
#define PLA_PREHEAT_HPB_TEMP 60
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
#define ABS_PREHEAT_HOTEND_TEMP 240
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
#define GUM_PREHEAT_HOTEND_TEMP 230
#define GUM_PREHEAT_HPB_TEMP 60
#define GUM_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
/*****************************************************************************************************/
#endif
......@@ -4,19 +4,8 @@
/*
* This configuration file contains all features that can be enabled.
*
* TEMPERATURE FEATURES:
* - Automatic temperature
* - Wattage report
* - Parallel heaters
* - Redundant thermistor
* - Temperature status LEDs
* - PID Settings - HOTEND
* - PID Settings - BED
* - Inverted PINS
* - Thermal runaway protection
* - Fan configuration
* - Mediancount (ONLY FOR DUE)
* EXTRUDER FEATURES:
* - Fan configuration
* - Default nominal filament diameter
* - Dangerous extrution prevention
* - Single nozzle
......@@ -51,6 +40,7 @@
* - Filament Runout sensor
* - Power consumption sensor
* - RFID card sensor
* - Flow sensor
* ADDON FEATURES:
* - EEPROM
* - SDCARD
......@@ -83,289 +73,9 @@
*/
//===========================================================================
//=========================== TEMPERATURE FEATURES ==========================
//============================= EXTRUDER FEATURES ===========================
//===========================================================================
/*****************************************************************************************
******************************** Automatic temperature **********************************
*****************************************************************************************
* *
* The hotend target temperature is calculated by all the buffered lines of gcode. *
* The maximum buffered steps/sec of the extruder motor is called "se". *
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor> *
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by *
* mintemp and maxtemp. Turn this off by excuting M109 without F* *
* Also, if the temperature is set to a value below mintemp, it will not be changed *
* by autotemp. *
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 *
* in the start.gcode *
* *
*****************************************************************************************/
#define AUTOTEMP
#define AUTOTEMP_OLDWEIGHT 0.98
/*****************************************************************************************/
/***********************************************************************
************************* Wattage report ******************************
***********************************************************************
* *
* If you want the M105 heater power reported in watts, *
* define the BED_WATTS, and (shared for all hotend) HOTEND_WATTS *
* *
***********************************************************************/
//#define HOTEND_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
/***********************************************************************/
/***********************************************************************
************************* Parallel heaters ******************************
***********************************************************************
* *
* Control heater 0 and heater 1 in parallel. *
* *
***********************************************************************/
//#define HEATERS_PARALLEL
/***********************************************************************/
/***********************************************************************
********************** Redundant thermistor ***************************
***********************************************************************
* *
* This makes temp sensor 1 a redundant sensor for sensor 0. *
* If the temperatures difference between these sensors is to high *
* the print will be aborted. *
* *
***********************************************************************/
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10 // (degC)
/***********************************************************************/
/***********************************************************************
********************* Temperature status LEDs *************************
***********************************************************************
* *
* Temperature status LEDs that display the hotend and bed *
* temperature. *
* Otherwise the RED led is on. There is 1C hysteresis. *
* *
***********************************************************************/
//#define TEMP_STAT_LEDS
/***********************************************************************/
/***********************************************************************
********************** PID Settings - HOTEND **************************
***********************************************************************
* *
* PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning *
* *
***********************************************************************/
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define K1 0.95 // Smoothing factor within the PID
#define MAX_OVERSHOOT_PID_AUTOTUNE 20 // Max valor for overshoot autotune
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
// If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_FUNCTIONAL_RANGE 10 // degC
#define PID_INTEGRAL_DRIVE_MAX PID_MAX // Limit for the integral term
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
//#define PID_ADD_EXTRUSION_RATE
#define LPQ_MAX_LEN 50
// HotEnd{HE0,HE1,HE2,HE3}
#define DEFAULT_Kp {40, 40, 40, 40} // Kp for H0, H1, H2, H3
#define DEFAULT_Ki {07, 07, 07, 07} // Ki for H0, H1, H2, H3
#define DEFAULT_Kd {60, 60, 60, 60} // Kd for H0, H1, H2, H3
#define DEFAULT_Kc {100, 100, 100, 100} // heating power = Kc * (e_speed)
/***********************************************************************/
/***********************************************************************
************************ PID Settings - COOLER ************************
***********************************************************************
* *
* PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning *
* Select PID or bang-bang with PIDTEMPCOOLER. *
* If bang-bang, COOLER_LIMIT_SWITCHING will enable hysteresis *
* *
***********************************************************************/
// Uncomment this to enable PID on the cooler. It uses the same frequency PWM as the extruder
// if you use a software PWM or the frequency you select if using an hardware PWM
// If your PID_dT is the default, you use a software PWM, 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 cooler.
// 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 PIDTEMPCOOLER
// Enable fast PWM for cooler
//#define FAST_PWM_COOLER
//#define COOLER_LIMIT_SWITCHING
#define COOLER_HYSTERESIS 2 //only disable heating if T<target-COOLER_HYSTERESIS and enable heating if T<target+COOLER_HYSTERESIS (works only if COOLER_LIMIT_SWITCHING is enabled)
#define COOLER_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
// This sets the max power delivered to the bed.
// 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,
// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPCOOLER)
#define MAX_COOLER_POWER 255 // limits duty cycle to bed; 255=full current
#define PID_COOLER_INTEGRAL_DRIVE_MAX MAX_COOLER_POWER // limit for the integral term
// 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_coolerKp 10.00
#define DEFAULT_coolerKi .023
#define DEFAULT_coolerKd 305.4
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
//#define PID_COOLER_DEBUG // Sends debug data to the serial port.
/***********************************************************************/
/***********************************************************************
************************ PID Settings - BED ***************************
***********************************************************************
* *
* PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning *
* 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 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
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS (works only if BED_LIMIT_SWITCHING is enabled)
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
// This sets the max power delivered to the bed.
// 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,
// 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
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER // limit for the integral term
// 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 10.00
#define DEFAULT_bedKi .023
#define DEFAULT_bedKd 305.4
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
//#define PID_BED_DEBUG // Sends debug data to the serial port.
/***********************************************************************/
/********************************************************************************
************************ Inverted Heater or Bed PINS ***************************
********************************************************************************
* *
* For inverted logical Heater or Bed pins *
* *
********************************************************************************/
//#define INVERTED_HEATER_PINS
//#define INVERTED_BED_PINS
/********************************************************************************
************************ Thermal runaway protection ****************************
********************************************************************************
* *
* This protects your device from damage and fire if a thermistor *
* falls out or temperature sensors fail in any way. *
* *
* The issue: If a thermistor falls out or a temperature sensor fails, *
* Marlin can no longer sense the actual temperature. Since a *
* disconnected thermistor reads as a low temperature, the firmware *
* will keep the heater/cooler on. *
* *
* The solution: Once the temperature reaches the target, start *
* observing. If the temperature stays too far below the *
* target(hysteresis) for too long, the firmware will halt *
* as a safety precaution. *
* *
* Uncomment THERMAL_PROTECTION_HOTENDS to enable this feature for all hotends. *
* Uncomment THERMAL_PROTECTION_BED to enable this feature for the heated bed. *
* Uncomment THERMAL_PROTECTION_COOLER to enable this feature for the cooler. *
* *
********************************************************************************/
//#define THERMAL_PROTECTION_HOTENDS
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
/**
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
* WATCH TEMP PERIOD to expire, and if the temperature hasn't increased by WATCH TEMP INCREASE
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
* but only if the current temperature is far enough below the target for a reliable test.
*
* If you get false positives for "Heating failed" increase WATCH TEMP PERIOD and/or decrease WATCH TEMP INCREASE
* WATCH TEMP INCREASE should not be below 2.
*/
#define WATCH_TEMP_PERIOD 20 // Seconds
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
/**
* Thermal Protection parameters for the bed are just as above for hotends.
*/
//#define THERMAL_PROTECTION_BED
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
//#define THERMAL_PROTECTION_COOLER
#define THERMAL_PROTECTION_COOLER_PERIOD 30 // Seconds
#define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degree Celsius
// Using M141 to set cooling temperature the firmware will wait for the WATCH_COOLER_TEMP_PERIOD
// to expire, and if the temperature hasn't lowered by WATCH_TEMP_DECREASE degrees,
// the machine is halted, requiring a hard reset. This test restarts with any M141,
// but only if the current remperature is far enough exceeding the target for a reliable test
// Enable this feature by uncomment THERMAL_PROTECTION_COOLER_WATCHDOG
//#define THERMAL_PROTECTION_COOLER_WATCHDOG
#define WATCH_TEMP_COOLER_PERIOD 60 // Seconds
#define WATCH_TEMP_COOLER_DECREASE 1 // Degree Celsius
/**
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
* WATCH BED TEMP PERIOD to expire, and if the temperature hasn't increased by WATCH BED TEMP INCREASE
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
* but only if the current temperature is far enough below the target for a reliable test.
*
* If you get too many "Heating failed" errors, increase WATCH BED TEMP PERIOD and/or decrease
* WATCH BED TEMP INCREASE. (WATCH BED TEMP INCREASE should not be below 2.)
*/
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
/********************************************************************************/
/**************************************************************************
**************************** Fan configuration ***************************
**************************************************************************/
......@@ -416,22 +126,6 @@
/**************************************************************************/
/**************************************************************************
**************************** MEDIAN COUNT ********************************
**************************************************************************
* *
* For Smoother temperature *
* ONLY FOR DUE *
**************************************************************************/
#define MEDIAN_COUNT 10
/**************************************************************************/
//===========================================================================
//============================= EXTRUDER FEATURES ===========================
//===========================================================================
/***********************************************************************
******************** DEFAULT NOMINAL FILAMENT DIA *********************
***********************************************************************
......@@ -1068,28 +762,6 @@
/**********************************************************************************/
/**************************************************************************
****************************** Flow sensor *******************************
**************************************************************************
* *
* Flow sensors for water circulators, usefull in case of coolers using *
* water or other liquid as heat vector *
* *
* Uncomment FLOWMETER_SENSOR to enable this feature *
* You also need to set FLOWMETER_PIN in Configurations_pins.h *
* *
**************************************************************************/
//#define FLOWMETER_SENSOR
#define FLOWMETER_MAXFLOW 6.0 // Liters per minute max
#define FLOWMETER_MAXFREQ 55 // frequency of pulses at max flow
// uncomment this to kill print job under the min flow rate, in liters/minute
//#define MINFLOW_PROTECTION 4
/**************************************************************************
*********************** Power consumption sensor *************************
**************************************************************************
......@@ -1174,6 +846,26 @@
/**************************************************************************/
/**************************************************************************
****************************** Flow sensor *******************************
**************************************************************************
* *
* Flow sensors for water circulators, usefull in case of coolers using *
* water or other liquid as heat vector *
* *
* Uncomment FLOWMETER SENSOR to enable this feature *
* You also need to set FLOWMETER PIN in Configurations_pins.h *
* *
**************************************************************************/
//#define FLOWMETER_SENSOR
#define FLOWMETER_MAXFLOW 6.0 // Liters per minute max
#define FLOWMETER_MAXFREQ 55 // frequency of pulses at max flow
// uncomment this to kill print job under the min flow rate, in liters/minute
//#define MINFLOW_PROTECTION 4
/**************************************************************************/
//===========================================================================
//============================= ADDON FEATURES ==============================
......@@ -1214,7 +906,7 @@
// as SD_DETECT_PIN in your board's pins definitions.
// This setting should be disabled unless you are using a push button, pulling the pin to ground.
// Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER).
#define SD_DETECT_INVERTED
//#define SD_DETECT_INVERTED
#define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers?
#define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place.
......@@ -1436,27 +1128,13 @@
**************************************************************************
* *
* Support for laser beam *
* Check also LASER_PWR_PIN and LASER_TTL_PIN in Configuration_pins.h *
* Check also LASER_PWR_PIN and LASER_TTL_PIN in Configuration_pins.h *
* *
**************************************************************************/
//#define LASERBEAM
/**************************************************************************/
/**************************************************************************
******************************* Laser **** *******************************
**************************************************************************
* *
* Support for laser beam *
* Check also Configuration_Laser.h *
* *
**************************************************************************/
//#define LASER
//#define LASERBEAM
/**************************************************************************/
//===========================================================================
//========================= ADVANCED MOTION FEATURES ========================
//===========================================================================
......
......@@ -4,17 +4,14 @@
//===========================================================================
//============================= Laser Settings ==============================
//===========================================================================
//
// Laser control is used by the Muve1 3D printer and the Buildlog.net laser cutter
//
//// The following define selects how to control the laser. Please choose the one that matches your setup.
// The following define selects how to control the laser.
// Please choose the one that matches your setup.
// 1 = Single pin control - LOW when off, HIGH when on, PWM to adjust intensity
// 2 = Two pin control - A firing pin for which LOW = off, HIGH = on, and a seperate intensity pin which carries a constant PWM signal and adjusts duty cycle to control intensity
// mUVe, buildlog.net and K40 chinese machines uses 2, AMRI ablative uses 1, AMRI SLS uses 2
#define LASER_CONTROL 2
#define LASER_CONTROL 1
/// The following define to use the new HakanBasted laser_pulse method to fire laser. It should be more efficient, but it's less tested.
// The following define to use the new HakanBasted laser_pulse method to fire laser. It should be more efficient, but it's less tested.
// Thanks for it to HakanBastedt that has implemented it for Marlin at https://github.com/HakanBastedt/Marlin
// Uncomment to enable it *USE AT YOUR OWN RISK*, it should work but it's *NOT WELL TESTED YET*
//#define LASER_PULSE_METHOD
......@@ -27,50 +24,32 @@
// At least some CO2-drivers need it, not sure about laserdiode drivers.
#define LASER_REMAP_INTENSITY 7
// Uncomment the following if your laser firing pin (not the PWM pin) for two pin control requires a HIGH signal to fire rather than a low (eg Red Sail M300 RS 3040)
/// #define HIGH_TO_FIRE
// #define HIGH_TO_FIRE
//// The following defines select which G codes tell the laser to fire. It's OK to uncomment more than one.
// The following defines select which G codes tell the laser to fire. It's OK to uncomment more than one.
#define LASER_FIRE_G1 10 // fire the laser on a G1 move, extinguish when the move ends
#define LASER_FIRE_SPINDLE 11 // fire the laser on M3, extinguish on M5
#define LASER_FIRE_E 12 // fire the laser when the E axis moves
//// Raster mode enables the laser to etch bitmap data at high speeds. Increases command buffer size substantially.
// Raster mode enables the laser to etch bitmap data at high speeds. Increases command buffer size substantially.
#define LASER_RASTER
#define LASER_MAX_RASTER_LINE 68 // maximum number of base64 encoded pixels per raster gcode command
#define LASER_MAX_RASTER_LINE 68 // Maximum number of base64 encoded pixels per raster gcode command
#define LASER_RASTER_ASPECT_RATIO 1 // pixels aren't square on most displays, 1.33 == 4:3 aspect ratio.
#define LASER_RASTER_MM_PER_PULSE 0.2 //Can be overridden by providing an R value in M649 command : M649 S17 B2 D0 R0.1 F4000
#define LASER_RASTER_MM_PER_PULSE 0.2 // Can be overridden by providing an R value in M649 command : M649 S17 B2 D0 R0.1 F4000
//// Uncomment the following if the laser cutter is equipped with a peripheral relay board
//// to control power to an exhaust fan, cooler pump, laser power supply, etc.
// Uncomment the following if the laser cutter is equipped with a peripheral relay board
// to control power to an exhaust fan, cooler pump, laser power supply, etc.
//#define LASER_PERIPHERALS
//#define LASER_PERIPHERALS_TIMEOUT 30000 // Number of milliseconds to wait for status signal from peripheral control board
//// Uncomment the following line to enable cubic bezier curve movement with the G5 code
// Uncomment the following line to enable cubic bezier curve movement with the G5 code
// #define G5_BEZIER
// Uncomment these options for the mUVe 1 3D printer
// #define CUSTOM_MENDEL_NAME "mUVe1 Printer"
// #define LASER_WATTS 0.05
// #define LASER_DIAMETER 0.1 // milimeters
// #define LASER_PWM 8000 // hertz
// #define MUVE_Z_PEEL // The mUVe 1 uses a special peel maneuver between each layer, it requires independent control of each Z motor
// Uncomment these options for the Buildlog.net laser cutter, and other similar models
#define CUSTOM_MENDEL_NAME "Laser Cutter"
#define LASER_WATTS 40.0
#define LASER_DIAMETER 0.1 // milimeters
#define LASER_PWM 50000 // hertz
#define LASER_FOCAL_HEIGHT 74.50 // z axis position at which the laser is focused
//Uncomment for AMRI Ablative or SLS
//#define CUSTOM_MENDEL_NAME "Laser Cutter"
//#define LASER_WATTS 40.0
//#define LASER_DIAMETER 0.1 // milimeters
//#define LASER_PWM 25000 // hertz
//#define LASER_FOCAL_HEIGHT 74.50 // z axis position at which the laser is focused
#endif
......@@ -69,6 +69,8 @@
#define HEATER_2_PIN ORIG_HEATER_2_PIN
#define HEATER_3_PIN ORIG_HEATER_3_PIN
#define HEATER_BED_PIN ORIG_HEATER_BED_PIN
#define HEATER_CHAMBER_PIN -1
#define COOLER_PIN -1
// TEMP pin
#define TEMP_0_PIN ORIG_TEMP_0_PIN
......@@ -76,6 +78,8 @@
#define TEMP_2_PIN ORIG_TEMP_2_PIN
#define TEMP_3_PIN ORIG_TEMP_3_PIN
#define TEMP_BED_PIN ORIG_TEMP_BED_PIN
#define TEMP_CHAMBER_PIN -1
#define TEMP_COOLER_PIN -1
// FAN pin
#define FAN_PIN ORIG_FAN_PIN
......@@ -106,35 +110,12 @@
#if ENABLED(LASERBEAM)
#define LASER_PWR_PIN -1
#define LASER_TTL_PIN -1
#endif
#if ENABLED(LASER)
#if LASER_CONTROL == 1
#define LASER_FIRING_PIN 5
#define LASER_INTENSITY_PIN -1
#endif
#if LASER_CONTROL == 2
#define LASER_INTENSITY_PIN 6 // Digital pins 2, 3, 5, 6, 7, 8 are attached to timers we can use
#define LASER_FIRING_PIN 5
#endif
#if DISABLED(ORIG_TEMP_COOLER_PIN)
#define TEMP_COOLER_PIN ORIG_TEMP_0_PIN // Default to the first thermistor
#endif
#if ENABLED(LASER_POWER_DOWN)
#define LASER_POWER_PIN 9 // This is currently hard-coded to timer2 which services pins 9, 10
#endif // LASER_POWER_DOWN
#if ENABLED(LASER_PERIPHERALS)
#define LASER_PERIPHERALS_PIN 11
#define LASER_PERIPHERALS_STATUS_PIN 4
#endif // LASER_PERIPHERALS
#if ENABLED(COOLER)
#define COOLER_PIN 2 // Digital pins 2, 3, 5, 6, 7, 8 are attached to timers we can use
#endif // COOLER
#define LASER_PERIPHERALS_PIN -1
#define LASER_PERIPHERALS_STATUS_PIN -1
#endif
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR)
#define FILRUNOUT_PIN -1
#endif
......
......@@ -94,7 +94,10 @@
*
* PIDTEMPBED:
* M304 PID bedKp, bedKi, bedKd
* M304 L PID coolerKp, coolerKi, coolerKd
* PIDTEMPCHAMBER
* M305 PID chamberKp, chamberKi, chamberKd
* PIDTEMPCOOLER
* M306 PID coolerKp, coolerKi, coolerKd
*
* DOGLCD:
* M250 C lcd_contrast
......@@ -232,6 +235,12 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, bedKd);
#endif
#if ENABLED(PIDTEMPCHAMBER)
EEPROM_WRITE_VAR(i, chamberKp);
EEPROM_WRITE_VAR(i, chamberKi);
EEPROM_WRITE_VAR(i, chamberKd);
#endif
#if ENABLED(PIDTEMPCOOLER)
EEPROM_WRITE_VAR(i, coolerKp);
EEPROM_WRITE_VAR(i, coolerKi);
......@@ -387,13 +396,18 @@ void Config_RetrieveSettings() {
EEPROM_READ_VAR(i, bedKd);
#endif
#if ENABLED(PIDTEMPCHAMBER)
EEPROM_READ_VAR(i, chamberKp);
EEPROM_READ_VAR(i, chamberKi);
EEPROM_READ_VAR(i, chamberKd);
#endif
#if ENABLED(PIDTEMPCOOLER)
EEPROM_READ_VAR(i, coolerKp);
EEPROM_READ_VAR(i, coolerKi);
EEPROM_READ_VAR(i, coolerKd);
#endif
#if HASNT(LCD_CONTRAST)
int lcd_contrast;
#endif
......@@ -588,13 +602,18 @@ void Config_ResetDefault() {
bedKd = scalePID_d(DEFAULT_bedKd);
#endif
#if ENABLED(PIDTEMPCHAMBER)
chamberKp = DEFAULT_chamberKp;
chamberKi = scalePID_i(DEFAULT_chamberKi);
chamberKd = scalePID_d(DEFAULT_chamberKd);
#endif
#if ENABLED(PIDTEMPCOOLER)
coolerKp = DEFAULT_coolerKp;
coolerKi = scalePID_i(DEFAULT_coolerKi);
coolerKd = scalePID_d(DEFAULT_coolerKd);
#endif
#if ENABLED(FWRETRACT)
autoretract_enabled = false;
retract_length = RETRACT_LENGTH;
......@@ -797,7 +816,7 @@ void Config_ResetDefault() {
ECHO_EM(" (Material GUM)");
#endif // ULTIPANEL
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCOOLER)
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCHAMBER) || ENABLED(PIDTEMPCOOLER)
if (!forReplay) {
ECHO_LM(CFG, "PID settings:");
}
......@@ -817,12 +836,17 @@ void Config_ResetDefault() {
#endif
#endif
#if ENABLED(PIDTEMPBED)
ECHO_SMV(CFG, " M304 P", bedKp); // for compatibility with hosts, only echos values for E0
ECHO_SMV(CFG, " M304 P", bedKp);
ECHO_MV(" I", unscalePID_i(bedKi));
ECHO_EMV(" D", unscalePID_d(bedKd));
#endif
#if ENABLED(PIDTEMPCHAMBER)
ECHO_SMV(CFG, " M305 P", chamberKp);
ECHO_MV(" I", unscalePID_i(chamberKi));
ECHO_EMV(" D", unscalePID_d(chamberKd));
#endif
#if ENABLED(PIDTEMPCOOLER)
ECHO_SMV(CFG, " M304 C P", coolerKp); // for compatibility with hosts, only echos values for E0
ECHO_SMV(CFG, " M306 P", coolerKp);
ECHO_MV(" I", unscalePID_i(coolerKi));
ECHO_EMV(" D", unscalePID_d(coolerKd));
#endif
......
#ifndef CONFIGURATION_TEMPERATURE_H
#define CONFIGURATION_TEMPERATURE_H
/*
* This configuration file contains basic settings.
*
* - Thermistor type
* - Temperature limits
* - Automatic temperature
* - Wattage report
* - Parallel heaters
* - Redundant thermistor
* - Temperature status LEDs
* - PID Settings - HOTEND
* - PID Settings - BED
* - PID Settings - CHAMBER
* - PID Settings - COOLER
* - Inverted PINS
* - Thermal runaway protection
* - Mediancount (ONLY FOR DUE)
*
*/
/*****************************************************************************************************
************************************** Thermistor type **********************************************
*****************************************************************************************************
* *
* 4.7kohm PULLUP! *
* This is a normal value, if you use a 1k pullup thermistor see below *
* Please choose the one that matches your setup and set to TEMP_SENSOR_. *
* *
* Temperature sensor settings (4.7kohm PULLUP): *
* -2 is thermocouple with MAX6675 (only for sensor 0) *
* -1 is thermocouple with AD595 or AD597 *
* 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 *
* 40 is the 10k Carel NTC015WH01 or ELIWELL SN8T6A1502 (4.7k pullup) *
* 60 is 100k Maker's Tool Works Kapton Bed Thermistor beta=3950 *
* *
* 1kohm PULLUP! *
* This is not normal, you would have to have changed out your 4.7k for 1k *
* (but gives greater accuracy and more stable PID) *
* Please choose the one that matches your setup. *
* *
* Temperature sensor settings (1kohm PULLUP): *
* 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) *
* 998 and 999 are Dummy Tables. ALWAYS read 25°C or DUMMY_THERMISTOR_998_VALUE temperature *
* *
*****************************************************************************************************/
#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
#define TEMP_SENSOR_CHAMBER 0 // NOT USED FOR NOW!!!
#define TEMP_SENSOR_COOLER 0
//These 2 defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
#define TEMP_SENSOR_AD595_OFFSET 0.0
#define TEMP_SENSOR_AD595_GAIN 1.0
// Use it for Testing or Development purposes. NEVER for production machine.
#define DUMMY_THERMISTOR_998_VALUE 25
#define DUMMY_THERMISTOR_999_VALUE 25
//Show Temperature ADC value
//The M105 command return, besides traditional information, the ADC value read from temperature sensors.
//#define SHOW_TEMP_ADC_VALUES
/*****************************************************************************************/
/******************************************************************************************************
************************************** Temperature limits ********************************************
******************************************************************************************************/
// Hotend temperature must be close to target for this long before M109 returns success
#define TEMP_RESIDENCY_TIME 10 // (seconds)
#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// Bed temperature must be close to target for this long before M190 returns success
#define TEMP_BED_RESIDENCY_TIME 0 // (seconds)
#define TEMP_BED_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_BED_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// Chamber temperature must be close to target for this long before M190 returns success
#define TEMP_CHAMBER_RESIDENCY_TIME 0 // (seconds)
#define TEMP_CHAMBER_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_CHAMBER_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// Cooler temperature must be close to target for this long before M190 returns success
#define TEMP_COOLER_RESIDENCY_TIME 0 // (seconds)
#define TEMP_COOLER_HYSTERESIS 1 // (degC) range of +/- temperatures considered "close" to the target one
#define TEMP_COOLER_WINDOW 1 // (degC) Window around target to start the residency timer x degC early.
// When temperature exceeds max temp, your heater will be switched off.
// When temperature exceeds max temp, your cooler cannot be activaed.
// 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 // (degC)
#define HEATER_1_MAXTEMP 275 // (degC)
#define HEATER_2_MAXTEMP 275 // (degC)
#define HEATER_3_MAXTEMP 275 // (degC)
#define BED_MAXTEMP 150 // (degC)
#define CHAMBER_MAXTEMP 100 // (degC)
#define COOLER_MAXTEMP 35 // (degC)
// The minimal temperature defines the temperature below which the heater will not be enabled It is used
// or, in case of cooler, it will switched off.
// 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 // (degC)
#define HEATER_1_MINTEMP 5 // (degC)
#define HEATER_2_MINTEMP 5 // (degC)
#define HEATER_3_MINTEMP 5 // (degC)
#define BED_MINTEMP 5 // (degC)
#define CHAMBER_MINTEMP 5 // (degC)
#define COOLER_MINTEMP 10 // (degC)
//Preheat Constants
#define PLA_PREHEAT_HOTEND_TEMP 190
#define PLA_PREHEAT_HPB_TEMP 60
#define PLA_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
#define ABS_PREHEAT_HOTEND_TEMP 240
#define ABS_PREHEAT_HPB_TEMP 100
#define ABS_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
#define GUM_PREHEAT_HOTEND_TEMP 230
#define GUM_PREHEAT_HPB_TEMP 60
#define GUM_PREHEAT_FAN_SPEED 255 // Insert Value between 0 and 255
/*****************************************************************************************/
/*****************************************************************************************
******************************** Automatic temperature **********************************
*****************************************************************************************
* *
* The hotend target temperature is calculated by all the buffered lines of gcode. *
* The maximum buffered steps/sec of the extruder motor is called "se". *
* Start autotemp mode with M109 S<mintemp> B<maxtemp> F<factor> *
* The target temperature is set to mintemp+factor*se[steps/sec] and is limited by *
* mintemp and maxtemp. Turn this off by excuting M109 without F* *
* Also, if the temperature is set to a value below mintemp, it will not be changed *
* by autotemp. *
* On an Ultimaker, some initial testing worked with M109 S215 B260 F1 *
* in the start.gcode *
* *
*****************************************************************************************/
#define AUTOTEMP
#define AUTOTEMP_OLDWEIGHT 0.98
/*****************************************************************************************/
/***********************************************************************
************************* Wattage report ******************************
***********************************************************************
* *
* If you want the M105 heater power reported in watts, *
* define the BED_WATTS, and (shared for all hotend) HOTEND_WATTS *
* *
***********************************************************************/
//#define HOTEND_WATTS (12.0*12.0/6.7) // P=I^2/R
//#define BED_WATTS (12.0*12.0/1.1) // P=I^2/R
/***********************************************************************/
/***********************************************************************
************************* Parallel heaters ******************************
***********************************************************************
* *
* Control heater 0 and heater 1 in parallel. *
* *
***********************************************************************/
//#define HEATERS_PARALLEL
/***********************************************************************/
/***********************************************************************
********************** Redundant thermistor ***************************
***********************************************************************
* *
* This makes temp sensor 1 a redundant sensor for sensor 0. *
* If the temperatures difference between these sensors is to high *
* the print will be aborted. *
* *
***********************************************************************/
//#define TEMP_SENSOR_1_AS_REDUNDANT
#define MAX_REDUNDANT_TEMP_SENSOR_DIFF 10 // (degC)
/***********************************************************************/
/***********************************************************************
********************* Temperature status LEDs *************************
***********************************************************************
* *
* Temperature status LEDs that display the hotend and bed *
* temperature. *
* Otherwise the RED led is on. There is 1C hysteresis. *
* *
***********************************************************************/
//#define TEMP_STAT_LEDS
/***********************************************************************/
/***********************************************************************
********************** PID Settings - HOTEND **************************
***********************************************************************
* *
* PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning *
* *
***********************************************************************/
#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current
#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current
#define K1 0.95 // Smoothing factor within the PID
#define MAX_OVERSHOOT_PID_AUTOTUNE 20 // Max valor for overshoot autotune
// Comment the following line to disable PID and enable bang-bang.
#define PIDTEMP
//#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result.
//#define PID_DEBUG // Sends debug data to the serial port.
//#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX
//#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay
// If the temperature difference between the target temperature and the actual temperature
// is more then PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max.
#define PID_FUNCTIONAL_RANGE 10 // degC
#define PID_INTEGRAL_DRIVE_MAX PID_MAX // Limit for the integral term
// this adds an experimental additional term to the heating power, proportional to the extrusion speed.
// if Kc is chosen well, the additional required power due to increased melting should be compensated.
//#define PID_ADD_EXTRUSION_RATE
#define LPQ_MAX_LEN 50
// HotEnd{HE0,HE1,HE2,HE3}
#define DEFAULT_Kp {40, 40, 40, 40} // Kp for H0, H1, H2, H3
#define DEFAULT_Ki {07, 07, 07, 07} // Ki for H0, H1, H2, H3
#define DEFAULT_Kd {60, 60, 60, 60} // Kd for H0, H1, H2, H3
#define DEFAULT_Kc {100, 100, 100, 100} // heating power = Kc * (e_speed)
/***********************************************************************/
/***********************************************************************
************************ PID Settings - BED ***************************
***********************************************************************
* *
* PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning *
* 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 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
#define BED_HYSTERESIS 2 //only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS (works only if BED_LIMIT_SWITCHING is enabled)
#define BED_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
// This sets the max power delivered to the bed.
// 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,
// 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
#define PID_BED_INTEGRAL_DRIVE_MAX MAX_BED_POWER // limit for the integral term
// 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 10.00
#define DEFAULT_bedKi 0.1
#define DEFAULT_bedKd 300.0
// FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles.
//#define PID_BED_DEBUG // Sends debug data to the serial port.
/***********************************************************************/
/***********************************************************************
************************ PID Settings - CHAMBER ***************************
***********************************************************************
* *
* PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning *
* Select PID or bang-bang with PIDTEMPCHAMBER. *
* If bang-bang, CHAMBER_LIMIT_SWITCHING will enable hysteresis *
* *
***********************************************************************/
// Uncomment this to enable PID on the chamber. It uses the same frequency PWM as the extruder.
// If your PID_dT 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 chamber PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
//#define PIDTEMPCHAMBER
//#define CHAMBER_LIMIT_SWITCHING
#define CHAMBER_HYSTERESIS 2 //only disable heating if T>target+CHAMBER_HYSTERESIS and enable heating if T>target-CHAMBER_HYSTERESIS (works only if CHAMBER_LIMIT_SWITCHING is enabled)
#define CHAMBER_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
// This sets the max power delivered to the chamber.
// all forms of chamber control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the chamber,
// so you shouldn't use it unless you are OK with PWM on your chamber. (see the comment on enabling PIDTEMPCHAMBER)
#define MAX_CHAMBER_POWER 255 // limits duty cycle to chamber; 255=full current
#define PID_CHAMBER_INTEGRAL_DRIVE_MAX MAX_CHAMBER_POWER // limit for the integral term
// 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_chamberKp 10.00
#define DEFAULT_chamberKi 0.1
#define DEFAULT_chamberKd 300.0
// FIND YOUR OWN: "M303 E-2 C8 S90" to run autotune on the chamber at 90 degreesC for 8 cycles.
//#define PID_CHAMBER_DEBUG // Sends debug data to the serial port.
/***********************************************************************/
/***********************************************************************
************************ PID Settings - COOLER ************************
***********************************************************************
* *
* PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning *
* Select PID or bang-bang with PIDTEMPCOOLER. *
* If bang-bang, COOLER_LIMIT_SWITCHING will enable hysteresis *
* *
***********************************************************************/
// Uncomment this to enable PID on the cooler. It uses the same frequency PWM as the extruder
// if you use a software PWM or the frequency you select if using an hardware PWM
// If your PID_dT is the default, you use a software PWM, 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 cooler.
// If your configuration is significantly different than this and you don't understand the issues involved, you probably
// shouldn't use cooler PID until someone else verifies your hardware works.
// If this is enabled, find your own PID constants below.
//#define PIDTEMPCOOLER
// Enable fast PWM for cooler
//#define FAST_PWM_COOLER
//#define COOLER_LIMIT_SWITCHING
#define COOLER_HYSTERESIS 2 //only disable heating if T<target-COOLER_HYSTERESIS and enable heating if T<target+COOLER_HYSTERESIS (works only if COOLER_LIMIT_SWITCHING is enabled)
#define COOLER_CHECK_INTERVAL 5000 //ms between checks in bang-bang control
// This sets the max power delivered to the cooler.
// all forms of cooler control obey this (PID, bang-bang, bang-bang with hysteresis)
// setting this to anything other than 255 enables a form of PWM to the cooler,
// so you shouldn't use it unless you are OK with PWM on your cooler. (see the comment on enabling PIDTEMPCOOLER)
#define MAX_COOLER_POWER 255 // limits duty cycle to cooler; 255=full current
#define PID_COOLER_INTEGRAL_DRIVE_MAX MAX_COOLER_POWER // limit for the integral term
// 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_coolerKp 10.00
#define DEFAULT_coolerKi .023
#define DEFAULT_coolerKd 305.4
// FIND YOUR OWN: "M303 E-3 C8 S90" to run autotune on the cooler at 90 degreesC for 8 cycles.
//#define PID_COOLER_DEBUG // Sends debug data to the serial port.
/***********************************************************************/
/********************************************************************************
**************************** Inverted PINS *************************************
********************************************************************************
* *
* For inverted logical Heater, Bed, Chamber or Cooler pins *
* *
********************************************************************************/
//#define INVERTED_HEATER_PINS
//#define INVERTED_BED_PIN
//#define INVERTED_CHAMBER_PIN
//#define INVERTED_COOLER_PIN
/********************************************************************************
************************ Thermal runaway protection ****************************
********************************************************************************
* *
* This protects your printer from damage and fire if a thermistor *
* falls out or temperature sensors fail in any way. *
* *
* The issue: If a thermistor falls out or a temperature sensor fails, *
* Marlin can no longer sense the actual temperature. Since a *
* disconnected thermistor reads as a low temperature, the firmware *
* will keep the heater/cooler on. *
* *
* The solution: Once the temperature reaches the target, start *
* observing. If the temperature stays too far below the *
* target(hysteresis) for too long, the firmware will halt *
* as a safety precaution. *
* *
* Uncomment THERMAL PROTECTION HOTENDS to enable this feature for all hotends. *
* Uncomment THERMAL PROTECTION BED to enable this feature for the heated bed. *
* Uncomment THERMAL PROTECTION CHAMBER to enable this feature for the chamber. *
* Uncomment THERMAL PROTECTION COOLER to enable this feature for the cooler. *
* *
********************************************************************************/
//#define THERMAL_PROTECTION_HOTENDS
#define THERMAL_PROTECTION_PERIOD 40 // Seconds
#define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius
/**
* Whenever an M104 or M109 increases the target temperature the firmware will wait for the
* WATCH TEMP PERIOD to expire, and if the temperature hasn't increased by WATCH TEMP INCREASE
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109,
* but only if the current temperature is far enough below the target for a reliable test.
*
* If you get false positives for "Heating failed" increase WATCH TEMP PERIOD and/or decrease WATCH TEMP INCREASE
* WATCH TEMP INCREASE should not be below 2.
*/
#define WATCH_TEMP_PERIOD 20 // Seconds
#define WATCH_TEMP_INCREASE 2 // Degrees Celsius
/**
* Thermal Protection parameters for the bed are just as above for hotends.
*/
//#define THERMAL_PROTECTION_BED
#define THERMAL_PROTECTION_BED_PERIOD 20 // Seconds
#define THERMAL_PROTECTION_BED_HYSTERESIS 2 // Degrees Celsius
/**
* Whenever an M140 or M190 increases the target temperature the firmware will wait for the
* WATCH BED TEMP PERIOD to expire, and if the temperature hasn't increased by WATCH BED TEMP INCREASE
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190,
* but only if the current temperature is far enough below the target for a reliable test.
*
* If you get too many "Heating failed" errors, increase WATCH BED TEMP PERIOD and/or decrease
* WATCH BED TEMP INCREASE. (WATCH BED TEMP INCREASE should not be below 2.)
*/
#define WATCH_BED_TEMP_PERIOD 60 // Seconds
#define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius
/**
* Thermal Protection parameters for the chamber
*/
//#define THERMAL_PROTECTION_CHAMBER
#define THERMAL_PROTECTION_CHAMBER_PERIOD 20 // Seconds
#define THERMAL_PROTECTION_CHAMBER_HYSTERESIS 2 // Degrees Celsius
/**
* Whenever an M141 or M191 increases the target temperature the firmware will wait for the
* WATCH CHAMBER TEMP PERIOD to expire, and if the temperature hasn't increased by WATCH CHAMBER TEMP INCREASE
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M141/M191,
* but only if the current temperature is far enough below the target for a reliable test.
*
* If you get too many "Heating failed" errors, increase WATCH CHAMBER TEMP PERIOD and/or decrease
* WATCH CHAMBER TEMP INCREASE. (WATCH CHAMBER TEMP INCREASE should not be below 2.)
*/
#define WATCH_CHAMBER_TEMP_PERIOD 60 // Seconds
#define WATCH_CHAMBER_TEMP_INCREASE 2 // Degrees Celsius
/**
* Thermal Protection parameters for the cooler.
*/
//#define THERMAL_PROTECTION_COOLER
#define THERMAL_PROTECTION_COOLER_PERIOD 30 // Seconds
#define THERMAL_PROTECTION_COOLER_HYSTERESIS 3 // Degree Celsius
/**
* Whenever an M142 or M192 increases the target temperature the firmware will wait for the
* WATCH COOLER TEMP PERIOD to expire, and if the temperature hasn't increased by WATCH COOLER TEMP INCREASE
* degrees, the machine is halted, requiring a hard reset. This test restarts with any M142/M192,
* but only if the current temperature is far enough below the target for a reliable test.
*
* If you get too many "Heating failed" errors, increase WATCH COOLER TEMP PERIOD and/or decrease
* WATCH COOLER TEMP INCREASE. (WATCH COOLER TEMP INCREASE should not be below 2.)
*/
#define WATCH_TEMP_COOLER_PERIOD 60 // Seconds
#define WATCH_TEMP_COOLER_DECREASE 1 // Degree Celsius
/********************************************************************************/
/**************************************************************************
**************************** MEDIAN COUNT ********************************
**************************************************************************
* *
* For Smoother temperature *
* ONLY FOR DUE *
**************************************************************************/
#define MEDIAN_COUNT 10
/**************************************************************************/
#endif
/**
* Marlin 3D Printer Firmware
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* MK & MK4due 3D Printer Firmware
*
* Based on Sprinter and grbl.
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
......@@ -24,7 +24,7 @@
#define CONFIGURATION_VERSION_H
#define FIRMWARE_NAME "MK"
#define SHORT_BUILD_VERSION "4.2.82_dev"
#define SHORT_BUILD_VERSION "4.2.83_dev"
#define BUILD_VERSION FIRMWARE_NAME "_" SHORT_BUILD_VERSION
#define STRING_DISTRIBUTION_DATE __DATE__ " " __TIME__ // build date and time
// It might also be appropriate to define a location where additional information can be found
......
......@@ -38,12 +38,12 @@
* G1 - Coordinated Movement X Y Z E, for laser move by firing
* G2 - CW ARC
* G3 - CCW ARC
* G4 - Dwell S<seconds> or P<milliseconds>
* G4 - Dwell S[seconds] or P[milliseconds], delay in Second or Millisecond
* G5 - Bezier curve - from http://forums.reprap.org/read.php?147,93577
* G7 - Execute laser raster line
* G7 - Laser raster base64
* G10 - retract filament according to settings of M207
* G11 - retract recover filament according to settings of M208
* G28 - Home one or more axes
* G28 - X Y Z Home all Axis. M for bed manual setting with LCD. B return to back point
* G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet.
* G30 - Single Z Probe, probes bed at current XY location. - Bed Probe and Delta geometry Autocalibration
* G31 - Dock sled (Z_PROBE_SLED only)
......@@ -98,15 +98,15 @@
* M98 - Print Hysteresis value
* M99 - Set Hysteresis parameter M99 X<in mm> Y<in mm> Z<in mm> E<in mm>
* M100 - Watch Free Memory (For Debugging Only)
* M104 - Set extruder target temp
* M104 - Set hotend target temp
* M105 - Read current temp
* M106 - Fan on
* M107 - Fan off
* M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating
* Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling
* M109 - Sxxx Wait for hotend current temp to reach target temp. Waits only when heating
* Rxxx Wait for hotend current temp to reach target temp. Waits when heating and cooling
* IF AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
* M110 - Set the current line number
* M111 - Set debug flags with S<mask>. See flag bits defined in Marlin.h.
* M111 - Set debug flags with S<mask>.
* M112 - Emergency stop
* M114 - Output current position to serial port
* M115 - Capabilities string
......@@ -119,15 +119,20 @@
* M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
* M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
* M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
* M140 - Set bed or cooler target temp
* M140 - Set hot bed target temp
* M141 - Set hot chamber target temp
* M142 - Set cooler target temp
* M145 - Set the heatup state H<hotend> B<bed> F<fan speed> for S<material> (0=PLA, 1=ABS)
* M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work.
* M163 - Set a single proportion for a mixing extruder. Requires COLOR_MIXING_EXTRUDER.
* M164 - Save the mix as a virtual extruder. Requires COLOR_MIXING_EXTRUDER and MIXING_VIRTUAL_TOOLS.
* M165 - Set the proportions for a mixing extruder. Use parameters ABCDHI to set the mixing factors. Requires COLOR_MIXING_EXTRUDER.
* M190 - Sxxx Wait for bed or cooler current temp to reach target temp. Waits only when heating Waits only when heating bed or cooling cooler
* Rxxx Wait for bed or cooler current temp to reach target temp. Waits when heating and cooling
* C parameter select Cooler, omitting it selec bed.
* M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
* Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
* M191 - Sxxx Wait for chamber current temp to reach target temp. Waits only when heating
* Rxxx Wait for chamber current temp to reach target temp. Waits when heating and cooling
* M192 - Sxxx Wait for cooler current temp to reach target temp. Waits only when heating
* Rxxx Wait for cooler current temp to reach target temp. Waits when heating and cooling
* M200 - set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).:D<millimeters>-
* M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
* M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!!
......@@ -140,8 +145,8 @@
* M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction.
* M218 - Set hotend offset (in mm): T<extruder_number> X<offset_on_X> Y<offset_on_Y>
* M220 - Set speed factor override percentage: S<factor in percent>
* M221 - Set extrude factor override percentage: S<factor in percent>
* M222 - Set density extrusion percentage for purge: S<factor in percent>
* M221 - T<extruder> S<factor in percent> - set extrude factor override percentage
* M222 - T<extruder> S<factor in percent> - set density extrude factor percentage for purge
* M226 - Wait until the specified pin reaches the state required: P<pin number> S<pin state>
* M240 - Trigger a camera to take a photograph
* M250 - Set LCD contrast C<contrast value> (value 0..63)
......@@ -150,7 +155,9 @@
* M301 - Set PID parameters P I D and C
* M302 - Allow cold extrudes, or set the minimum extrude S<temperature>.
* M303 - PID relay autotune S<temperature> sets the target temperature (default target temperature = 150C). H<hotend> C<cycles> U<Apply result>
* M304 - Set bed PID parameters P I and D or cooling if C parameter
* M304 - Set hot bed PID parameters P I and D
* M305 - Set hot chamber PID parameters P I and D
* M306 - Set cooler PID parameters P I and D
* M350 - Set microstepping mode.
* M351 - Toggle MS1 MS2 pins directly.
* M380 - Activate solenoid on active extruder
......@@ -175,8 +182,6 @@
* M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
* M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
* M649 - laser set options
* M650 - mUVe peel set peel distance
* M651 - mUVe peel run peel move
* M666 - Set z probe offset or Endstop and delta geometry adjustment
* M906 - Set motor currents XYZ T0-4 E
* M907 - Set digital trimpot motor current using axis codes.
......
......@@ -35,14 +35,14 @@
#include "Configuration_Scara.h"
#endif
#include "Configuration_Temperature.h"
#include "Configuration_Feature.h"
#include "Configuration_Overall.h"
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
#include "Configuration_Laser.h"
#if ENABLED(LASER_RASTER)
#include "module/base64/Base64.h"
#include "module/laser/base64/base64.h"
#endif
#include "module/laser/laser.h"
#endif
......@@ -65,7 +65,7 @@
#include "module/motion/qr_solve.h"
#include "module/motion/cartesian_correction.h"
#include "module/temperature/temperature.h"
#include "module/flowmeter/flowmeter.h"
#include "module/sensor/flowmeter.h"
#include "module/temperature/thermistortables.h"
#include "module/lcd/ultralcd.h"
#include "module/lcd/buzzer.h"
......
/*
HardwareSerial.h - Hardware serial library for Wiring
Copyright (c) 2006 Nicholas Zambetti. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
Modified 28 September 2010 by Mark Sproul
*/
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* HardwareSerial.h - Hardware serial library for Wiring
* Copyright (c) 2006 Nicholas Zambetti. All right reserved.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 2.1 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*
* Modified 28 September 2010 by Mark Sproul
* Modified 3 March 2015 by MagoKimbra
*/
#ifndef HardwareSerial_H
#define HardwareSerial_H
......
......@@ -290,10 +290,6 @@ bool software_endstops = true;
unsigned long stoppower = 0;
#endif
#if ENABLED(LASERBEAM)
int laser_ttl_modulation = 0;
#endif
#if ENABLED(NPR2)
static float color_position[] = COLOR_STEP;
static float color_step_moltiplicator = (DRIVER_MICROSTEP / MOTOR_ANGLE) * CARTER_MOLTIPLICATOR;
......@@ -535,13 +531,6 @@ bool enqueue_and_echo_command(const char* cmd, bool say_ok/*=false*/) {
}
#endif
#if ENABLED(LASERBEAM)
void setup_laserbeampin() {
OUT_WRITE(LASER_PWR_PIN, LOW);
OUT_WRITE(LASER_TTL_PIN, LOW);
}
#endif
#if HAS(POWER_SWITCH)
void setup_powerhold() {
#if HAS(SUICIDE)
......@@ -715,10 +704,6 @@ void setup() {
setup_photpin();
#endif
#if ENABLED(LASERBEAM)
setup_laserbeampin();
#endif
#if HAS(SERVOS)
servo_init();
#endif
......@@ -743,13 +728,13 @@ void setup() {
setup_statled();
#endif
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
laser_init();
#endif
#if ENABLED(FLOWMETER_SENSOR)
#if ENABLED(MINFLOW_PROTECTION)
flow_firstread=false;
flow_firstread = false;
#endif
flow_init();
#endif
......@@ -775,7 +760,6 @@ void setup() {
#if ENABLED(FIRMWARE_TEST)
FirmwareTest();
#endif
}
/**
......@@ -1326,21 +1310,13 @@ inline void line_to_z(float zPosition) {
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], zPosition, current_position[E_AXIS], feedrate/60, active_extruder, active_driver);
}
inline void line_to_destination(float mm_m) {
#if ENABLED(LASER) && ENABLED(MUVE_Z_PEEL)
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[Z_AXIS], mm_m/60, active_extruder, active_driver);
#else
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], mm_m/60, active_extruder, active_driver);
#endif
}
inline void line_to_destination() {
line_to_destination(feedrate);
}
inline void sync_plan_position() {
#if ENABLED(LASER) && ENABLED(MUVE_Z_PEEL)
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[Z_AXIS]);
#else
plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
#endif
}
#if MECH(DELTA) || MECH(SCARA)
inline void sync_plan_position_delta() {
......@@ -1662,13 +1638,12 @@ inline void do_blocking_move_to_z(float z) { do_blocking_move_to(current_positio
#endif
home_dir(axis);
#if ENABLED(LASER) && (LASER_HAS_FOCUS == false)
#if ENABLED(LASERBEAM) && (LASER_HAS_FOCUS == false)
if (axis == Z_AXIS) goto AvoidLaserFocus;
#endif
// Set the axis position as setup for the move
current_position[axis] = 0;
sync_plan_position();
#if HAS(Z_PROBE_SLED)
......@@ -1791,9 +1766,11 @@ inline void do_blocking_move_to_z(float z) { do_blocking_move_to(current_positio
#endif
}
}
#if ENABLED(LASER) && (LASER_HAS_FOCUS == false)
AvoidLaserFocus:
#if ENABLED(LASERBEAM) && (LASER_HAS_FOCUS == false)
AvoidLaserFocus:
#endif
if (DEBUGGING(INFO)) {
ECHO_SMV(INFO, "<<< homeaxis(", (unsigned long)axis);
ECHO_EM(")");
......@@ -2922,9 +2899,9 @@ AvoidLaserFocus:
#if HAS(TEMP_BED)
ECHO_M(SERIAL_BAT);
#if ENABLED(BED_WATTS)
ECHO_VM(((BED_WATTS) * getHeaterPower(-1)) / 127, "W");
ECHO_VM(((BED_WATTS) * getBedPower()) / 127, "W");
#else
ECHO_V(getHeaterPower(-1));
ECHO_V(getBedPower());
#endif
#endif
ECHO_M(SERIAL_AT ":");
......@@ -2959,8 +2936,26 @@ AvoidLaserFocus:
}
#endif
#if HAS(TEMP_CHAMBER)
void print_chamberstate() {
ECHO_M(" CHAMBER: ");
ECHO_MV(SERIAL_C, degChamber(), 1);
ECHO_MV(" /", degTargetChamber(), 1);
ECHO_M(SERIAL_CAT);
#if ENABLED(CHAMBER_WATTS)
ECHO_VM(((CHAMBER_WATTS) * getChamberPower()) / 127, "W");
#else
ECHO_V(getChamberPower());
#endif
#if ENABLED(SHOW_TEMP_ADC_VALUES)
ECHO_MV(" ADC C:", degChamber(), 1);
ECHO_MV("C->", rawChamberTemp() / OVERSAMPLENR, 0);
#endif
}
#endif // HAS(TEMP_CHAMBER)
#if HAS(TEMP_COOLER)
void print_coolerstates() {
void print_coolerstate() {
ECHO_M(" COOL: ");
ECHO_MV(SERIAL_C, degCooler(), 1);
ECHO_MV(" /", degTargetCooler(), 1);
......@@ -2978,13 +2973,14 @@ AvoidLaserFocus:
#endif // HAS(TEMP_COOLER)
#if ENABLED(FLOWMETER_SENSOR)
void print_flowratestates() {
float readval;
readval = get_flowrate();
void print_flowratestate() {
float readval = get_flowrate();
#if ENABLED(MINFLOW_PROTECTION)
if(readval > MINFLOW_PROTECTION)
flow_firstread=true;
flow_firstread = true;
#endif
ECHO_MV(" FLOW: ", readval);
ECHO_M(" l/min ");
}
......@@ -3138,6 +3134,79 @@ inline void wait_bed(bool no_wait_for_cooling = true) {
KEEPALIVE_STATE(IN_HANDLER);
}
#if HAS(TEMP_CHAMBER)
inline void wait_chamber(bool no_wait_for_heating = true) {
#if TEMP_CHAMBER_RESIDENCY_TIME > 0
millis_t residency_start_ms = 0;
// Loop until the temperature has stabilized
#define TEMP_CHAMBER_CONDITIONS (!residency_start_ms || PENDING(now, residency_start_ms + (TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL))
#else
// Loop until the temperature is very close target
#define TEMP_CHAMBER_CONDITIONS (wants_to_heat ? isHeatingChamber() : isCoolingChamber())
#endif
float theTarget = -1;
bool wants_to_heat;
cancel_cooldown = false;
millis_t now, next_temp_ms = 0;
KEEPALIVE_STATE(NOT_BUSY);
// Wait for temperature to come close enough
do {
now = millis();
if (ELAPSED(now, next_temp_ms)) { //Print Temp Reading every 1 second while heating up.
next_temp_ms = now + 1000UL;
print_chamberstate();
#if TEMP_CHAMBER_RESIDENCY_TIME > 0
ECHO_M(SERIAL_W);
if (residency_start_ms) {
long rem = (((TEMP_CHAMBER_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL;
ECHO_EV(rem);
}
else {
ECHO_EM("?");
}
#else
ECHO_E;
#endif
}
// Target temperature might be changed during the loop
if (theTarget != degTargetChamber()) {
wants_to_heat = isHeatingChamber();
theTarget = degTargetChamber();
// Exit if S<higher>, continue if S<lower>, R<higher>, or R<lower>
if (no_wait_for_heating && wants_to_heat) break;
// Prevent a wait-forever situation if R is misused i.e. M190 C R50
// Simply don't wait to heat a chamber over 25C
if (wants_to_heat && theTarget > 25) break;
}
idle();
refresh_cmd_timeout(); // to prevent stepper_inactive_time from running out
#if TEMP_CHAMBER_RESIDENCY_TIME > 0
float temp_diff = fabs(degTargetBed() - theTarget);
if (!residency_start_ms) {
// Start the TEMP_CHAMBER_RESIDENCY_TIME timer when we reach target temp for the first time.
if (temp_diff < TEMP_CHAMBER_WINDOW) residency_start_ms = millis();
}
else if (temp_diff > TEMP_CHAMBER_HYSTERESIS) {
// Restart the timer whenever the temperature falls outside the hysteresis.
residency_start_ms = millis();
}
#endif //TEMP_CHAMBER_RESIDENCY_TIME > 0
} while (!cancel_cooldown && TEMP_CHAMBER_CONDITIONS);
LCD_MESSAGEPGM(MSG_CHAMBER_DONE);
KEEPALIVE_STATE(IN_HANDLER);
}
#endif
#if HAS(TEMP_COOLER)
inline void wait_cooler(bool no_wait_for_heating = true) {
#if TEMP_COOLER_RESIDENCY_TIME > 0
......@@ -3161,7 +3230,7 @@ inline void wait_bed(bool no_wait_for_cooling = true) {
now = millis();
if (ELAPSED(now, next_temp_ms)) { //Print Temp Reading every 1 second while heating up.
next_temp_ms = now + 1000UL;
print_coolerstates();
print_coolerstate();
#if TEMP_COOLER_RESIDENCY_TIME > 0
ECHO_M(SERIAL_W);
if (residency_start_ms) {
......@@ -3330,8 +3399,9 @@ inline void gcode_G0_G1(bool lfire) {
return;
}
}
#endif //FWRETRACT
#if ENABLED(LASER) && ENABLED(LASER_FIRE_G1)
#endif // FWRETRACT
#if ENABLED(LASERBEAM) && ENABLED(LASER_FIRE_G1)
if(lfire) {
if (code_seen('S') && IsRunning()) laser.intensity = (float) code_value();
if (code_seen('L') && IsRunning()) laser.duration = (unsigned long) labs(code_value());
......@@ -3346,10 +3416,8 @@ inline void gcode_G0_G1(bool lfire) {
prepare_move();
#if ENABLED(LASER) && ENABLED(LASER_FIRE_G1)
if(lfire) {
laser.status = LASER_OFF;
}
#if ENABLED(LASERBEAM) && ENABLED(LASER_FIRE_G1)
if(lfire) laser.status = LASER_OFF;
#endif
}
......@@ -3369,7 +3437,7 @@ inline void gcode_G2_G3(bool clockwise) {
gcode_get_destination();
#if ENABLED(LASER) && ENABLED(LASER_FIRE_G1)
#if ENABLED(LASERBEAM) && ENABLED(LASER_FIRE_G1)
if (code_seen('S') && IsRunning()) laser.intensity = (float) code_value();
if (code_seen('L') && IsRunning()) laser.duration = (unsigned long) labs(code_value());
if (code_seen('P') && IsRunning()) laser.ppm = (float) code_value();
......@@ -3380,7 +3448,6 @@ inline void gcode_G2_G3(bool clockwise) {
laser.fired = LASER_FIRE_G1;
#endif
#if ENABLED(SF_ARC_FIX)
relative_mode = relative_mode_backup;
#endif
......@@ -3395,7 +3462,8 @@ inline void gcode_G2_G3(bool clockwise) {
plan_arc(destination, arc_offset, clockwise);
refresh_cmd_timeout();
#if ENABLED(LASER) && ENABLED(LASER_FIRE_G1)
#if ENABLED(LASERBEAM) && ENABLED(LASER_FIRE_G1)
laser.status = LASER_OFF;
#endif
......@@ -3442,7 +3510,7 @@ inline void gcode_G4() {
#endif //FWRETRACT
#if ENABLED(G5_BEZIER)
inline void gcode_G5() {
inline void gcode_G5() {
float p[4][2] = {{0.0,0.0},{0.0,0.0},{0.0,0.0},{0.0,0.0}};
int steps = 10;
float stepsPerUnit = 1;
......@@ -3481,27 +3549,34 @@ inline void gcode_G5() {
log_float("X", p[3][0]);
log_float("Y", p[3][1]);
#endif
// calc num steps
float maxD = 0, sqrD = 0;
for (int i=1; i<4; i++) {
sqrD = (p[i][0] - p[i-1][0])*(p[i][0] - p[i-1][0]) + (p[i][1] - p[i-1][1])*(p[i][1] - p[i-1][1]);
if (sqrD > maxD) {maxD = sqrD; };
}
maxD = sqrt(maxD);
if (maxD > 0) {
if (maxD > 0)
steps = round((3 * maxD * stepsPerUnit));
}
if (steps < 1) steps = 1;
if (steps > 200) steps = 200;
if (steps < 1)
steps = 1;
if (steps > 200)
steps = 200;
#ifdef DEBUG
log_float("maxD",maxD);
log_int("steps", steps);
#endif
// init Forward Differencing algo
//---------------------------------------
t = 1.0 / steps;
temp = t*t;
for (int i=0; i<2; i++) {
for (int i = 0; i < 2; i++) {
f[i] = p[0][i];
fd[i] = 3 * (p[1][i] - p[0][i]) * t;
fdd_per_2[i] = 3 * (p[0][i] - 2 * p[1][i] + p[2][i]) * temp;
......@@ -3511,15 +3586,18 @@ inline void gcode_G5() {
fdd[i] = fdd_per_2[i] + fdd_per_2[i];
fddd_per_6[i] = (fddd_per_2[i] * (1.0 / 3));
}
// prep destination
for(int i=0; i < NUM_AXIS; i++) {
for(int i = 0; i < NUM_AXIS; i++) {
destination[i] = current_position[i];
}
// iterate through curve
//---------------------------------------
for (int loop=0; loop < steps; loop++) {
for (int loop = 0; loop < steps; loop++) {
destination[0] = f[0];
destination[1] = f[1];
#ifdef DEBUG
log_float("X",f[0]);
log_float("Y",f[1]);
......@@ -3535,44 +3613,46 @@ inline void gcode_G5() {
fdd_per_2[i] = fdd_per_2[i] + fddd_per_2[i];
}
}
// Move to final position
destination[0] = p[3][0];
destination[1] = p[3][1];
prepare_move();
previous_millis_cmd = millis();
}
}
#endif
#if ENABLED(LASER) && ENABLED(LASER_RASTER)
inline void gcode_G7() {
#if ENABLED(LASERBEAM) && ENABLED(LASER_RASTER)
inline void gcode_G7() {
if (code_seen('L')) laser.raster_raw_length = int(code_value());
if (code_seen('$')) {
laser.raster_direction = (bool)code_value();
destination[Y_AXIS] = current_position[Y_AXIS] + (laser.raster_mm_per_pulse * laser.raster_aspect_ratio); // increment Y axis
}
if (code_seen('D')) laser.raster_num_pixels = base64_decode(laser.raster_data, seen_pointer+1, laser.raster_raw_length);
if (!laser.raster_direction) {
destination[X_AXIS] = current_position[X_AXIS] - (laser.raster_mm_per_pulse * laser.raster_num_pixels);
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(INFO, "Negative Raster Line");
}
} else {
else {
destination[X_AXIS] = current_position[X_AXIS] + (laser.raster_mm_per_pulse * laser.raster_num_pixels);
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(INFO, "Positive Raster Line");
}
}
laser.ppm = 1 / laser.raster_mm_per_pulse; //number of pulses per millimetre
laser.ppm = 1 / laser.raster_mm_per_pulse; // number of pulses per millimetre
laser.duration = (1000000 / ( feedrate / 60)) / laser.ppm; // (1 second in microseconds / (time to move 1mm in microseconds)) / (pulses per mm) = Duration of pulse, taking into account feedrate as speed and ppm
laser.mode = RASTER;
laser.status = LASER_ON;
laser.fired = RASTER;
prepare_move();
}
}
#endif
/**
......@@ -4418,6 +4498,7 @@ inline void gcode_G28() {
enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT));
st_synchronize();
#endif
KEEPALIVE_STATE(IN_HANDLER);
if (DEBUGGING(INFO)) ECHO_LM(INFO, "<<< gcode_G29");
......@@ -4786,10 +4867,9 @@ inline void gcode_G92() {
current_position[i] = v;
if (i == E_AXIS) {
#if DISABLED(MUVE_Z_PEEL)
plan_set_e_position(v);
#endif
} else {
}
else {
position_shift[i] += v - p; // Offset the coordinate space
update_software_endstops((AxisEnum)i);
didXYZ = true;
......@@ -4860,20 +4940,11 @@ inline void gcode_G92() {
}
#endif //ULTIPANEL
#if (ENABLED(LASERBEAM) || ENABLED(LASER) && ENABLED(LASER_FIRE_SPINDLE))
#if (ENABLED(LASERBEAM) && ENABLED(LASER_FIRE_SPINDLE))
/**
* M3: S - Setting laser beam or fire laser
*/
inline void gcode_M3() {
#if ENABLED(LASERBEAM)
if (code_seen('S')) {
laser_ttl_modulation = constrain(code_value(), 0, 255);
}
else {
laser_ttl_modulation = 0;
}
#endif
#if ENABLED(LASER) && ENABLED(LASER_FIRE_SPINDLE)
inline void gcode_M3_M4() {
if (code_seen('S') && IsRunning()) laser.intensity = (float) code_value();
if (code_seen('L') && IsRunning()) laser.duration = (unsigned long) labs(code_value());
if (code_seen('P') && IsRunning()) laser.ppm = (float) code_value();
......@@ -4886,44 +4957,26 @@ inline void gcode_G92() {
lcd_update();
prepare_move();
#endif
}
/**
* M4: Turn on laser beam
*/
inline void gcode_M4() {
#if ENABLED(LASERBEAM)
WRITE(LASER_PWR_PIN, HIGH);
laser_ttl_modulation = 0;
#endif
#if ENABLED(LASER) && ENABLED(LASER_FIRE_SPINDLE)
gcode_M3();
#endif
}
/**
* M5: Turn off laser beam
*/
inline void gcode_M5() {
#if ENABLED(LASERBEAM)
WRITE(LASER_PWR_PIN, LOW);
laser_ttl_modulation = 0;
#endif
#if ENABLED(LASER) && ENABLED(LASER_FIRE_SPINDLE)
if(laser.status != LASER_OFF) {
if (laser.status != LASER_OFF) {
laser.status = LASER_OFF;
laser.mode = CONTINUOUS;
laser.duration = 0;
lcd_update();
prepare_move();
if(laser.diagnostics) ECHO_LM(INFO, "Laser M5 called and laser ON");
if (laser.diagnostics)
ECHO_LM(INFO, "Laser M5 called and laser OFF");
}
#endif
}
#endif //LASERBEAM
#endif // LASERBEAM
/**
* M11: Start/Stop printing serial mode
......@@ -5425,7 +5478,8 @@ inline void gcode_M78() {
LCD_MESSAGEPGM(WELCOME_MSG);
lcd_update();
#endif
#if ENABLED(LASER_PERIPHERALS)
#if ENABLED(LASERBEAM) && ENABLED(LASER_PERIPHERALS)
laser_peripherals_on();
laser_wait_for_peripherals();
#endif
......@@ -5444,16 +5498,15 @@ inline void gcode_M81() {
disable_e();
finishAndDisableSteppers();
fanSpeed = 0;
#if ENABLED(LASERBEAM)
laser_ttl_modulation = 0;
#endif
#ifdef LASER
laser_extinguish();
#endif
#ifdef LASER_PERIPHERALS
#if ENABLED(LASER_PERIPHERALS)
laser_peripherals_off();
#endif
#endif
delay_ms(1000); // Wait 1 second before switching off
#if HAS(SUICIDE)
st_synchronize();
suicide();
......@@ -5461,6 +5514,7 @@ inline void gcode_M81() {
OUT_WRITE(PS_ON_PIN, PS_ON_ASLEEP);
powersupply = false;
#endif
#if ENABLED(ULTIPANEL)
LCD_MESSAGEPGM(MACHINE_NAME " " MSG_OFF ".");
lcd_update();
......@@ -5803,11 +5857,14 @@ inline void gcode_M105() {
#if HAS(TEMP_0) || HAS(TEMP_BED) || ENABLED(HEATER_0_USES_MAX6675)
print_heaterstates();
#endif
#if HAS(TEMP_CHAMBER)
print_chamberstate();
#endif
#if HAS(TEMP_COOLER)
print_coolerstates();
print_coolerstate();
#endif
#if ENABLED(FLOWMETER_SENSOR)
print_flowratestates();
print_flowratestate();
#endif
#else // HASNT(TEMP_0) && HASNT(TEMP_BED)
ECHO_LM(ER, SERIAL_ERR_NO_THERMISTORS);
......@@ -5830,8 +5887,8 @@ inline void gcode_M105() {
#endif // HAS(FAN)
/**
* M109: Sxxx Wait for extruder(s) to reach temperature. Waits only when heating.
* Rxxx Wait for extruder(s) to reach temperature. Waits when heating and cooling.
* M109: Sxxx Wait for hotend(s) to reach temperature. Waits only when heating.
* Rxxx Wait for hotend(s) to reach temperature. Waits when heating and cooling.
*/
inline void gcode_M109() {
if (get_target_extruder_from_command(109)) return;
......@@ -6002,19 +6059,35 @@ inline void gcode_M122() {
#endif
#endif //BARICUDA
/**
* M140: Set bed or cooler temperature
#if HAS(TEMP_BED)
/**
* M140: Set Bed temperature
*/
inline void gcode_M140() {
inline void gcode_M140() {
if (DEBUGGING(DRYRUN)) return;
if (code_seen('C')) {
if (code_seen('S')) setTargetCooler(code_value());
}
else {
if (code_seen('S')) setTargetBed(code_value());
}
#endif
}
#if HAS(TEMP_CHAMBER)
/**
* M141: Set Chamber temperature
*/
inline void gcode_M141() {
if (DEBUGGING(DRYRUN)) return;
if (code_seen('S')) setTargetChamber(code_value());
}
#endif
#if HAS(TEMP_COOLER)
/**
* M142: Set Cooler temperature
*/
inline void gcode_M142() {
if (DEBUGGING(DRYRUN)) return;
if (code_seen('S')) setTargetCooler(code_value());
}
#endif
#if ENABLED(ULTIPANEL) && TEMP_SENSOR_0 != 0
/**
......@@ -6160,40 +6233,54 @@ inline void gcode_M140() {
inline void gcode_M165() { gcode_get_mix(); }
#endif // COLOR_MIXING_EXTRUDER
#if HAS(TEMP_BED) || HAS(TEMP_COOLER)
#if HAS(TEMP_BED)
/**
* M190: Sxxx Wait for bed or cooler current temp to reach target temp. Waits only when heating for bed, cooling for cooler
* Rxxx Wait for bed or cooler current temp to reach target temp. Waits when heating and cooling
* C select cooler, omitting select bed
*
* M190: Sxxx Wait for bed current temp to reach target temp. Waits only when heating
* Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
*/
inline void gcode_M190() {
if (DEBUGGING(DRYRUN)) return;
#if HAS(TEMP_COOLER)
if (code_seen('C')) {
LCD_MESSAGEPGM(MSG_COOLER_COOLING);
bool no_wait_for_heating = code_seen('S');
if (no_wait_for_heating || code_seen('R')) setTargetCooler(code_value());
wait_cooler(no_wait_for_heating);
}
#endif
#if HAS(TEMP_BED) && HAS(TEMP_COOLER)
else {
#elif HAS(TEMP_BED)
if (!code_seen('C')) {
#endif
#if HAS(TEMP_BED)
LCD_MESSAGEPGM(MSG_BED_HEATING);
bool no_wait_for_cooling = code_seen('S');
if (no_wait_for_cooling || code_seen('R')) setTargetBed(code_value());
wait_bed(no_wait_for_cooling);
}
#endif
}
#endif // HAS(TEMP_BED)
#if HAS(TEMP_CHAMBER)
/**
* M191: Sxxx Wait for chamber current temp to reach target temp. Waits only when heating
* Rxxx Wait for chamber current temp to reach target temp. Waits when heating and cooling
*/
inline void gcode_M191() {
if (DEBUGGING(DRYRUN)) return;
LCD_MESSAGEPGM(MSG_CHAMBER_HEATING);
bool no_wait_for_cooling = code_seen('S');
if (no_wait_for_cooling || code_seen('R')) setTargetChamber(code_value());
wait_chamber(no_wait_for_cooling);
}
#endif // HAS(TEMP_CHAMBER)
#if HAS(TEMP_COOLER)
/**
* M192: Sxxx Wait for cooler current temp to reach target temp. Waits only when heating
* Rxxx Wait for cooler current temp to reach target temp. Waits when heating and cooling
*/
inline void gcode_M192() {
if (DEBUGGING(DRYRUN)) return;
LCD_MESSAGEPGM(MSG_COOLER_COOLING);
bool no_wait_for_heating = code_seen('S');
if (no_wait_for_heating || code_seen('R')) setTargetCooler(code_value());
wait_cooler(no_wait_for_heating);
}
#endif
/**
* M200: Set filament diameter and set E axis units to cubic millimetres
*
......@@ -6254,7 +6341,6 @@ inline void gcode_M201() {
}
#endif
/**
* M203: Set maximum feedrate that your machine can sustain in mm/sec
*
......@@ -6656,7 +6742,7 @@ inline void gcode_M226() {
/**
* M303: PID relay autotune
* S<temperature> sets the target temperature. (default target temperature = 150C)
* H<hotend> (-1 for the bed, -2 for cooler) (default 0)
* H<hotend> (-1 for the bed, -2 for chamber, -3 for cooler) (default 0)
* C<cycles>
* U<bool> with a non-zero value will apply the result to current settings
*/
......@@ -6672,30 +6758,14 @@ inline void gcode_M226() {
KEEPALIVE_STATE(NOT_BUSY); // don't send "busy: processing" messages during autotune output
PID_autotune(temp, h, c, u);
KEEPALIVE_STATE(IN_HANDLER);
}
#endif
#if ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCOOLER)
#if ENABLED(PIDTEMPBED)
// M304: Set bed PID parameters P I and D
inline void gcode_M304() {
#if ENABLED(PIDTEMPCOOLER)
if (code_seen('C')) {
if (code_seen('P')) coolerKp = code_value();
if (code_seen('I')) coolerKi = scalePID_i(code_value());
if (code_seen('D')) coolerKd = scalePID_d(code_value());
updatePID();
ECHO_SMV(OK, " C p:", coolerKp);
ECHO_MV(" i:", unscalePID_i(coolerKi));
ECHO_EMV(" d:", unscalePID_d(coolerKd));
}
#endif
#if ENABLED(PIDTEMPCOOLER) && ENABLED(PIDTEMPBED)
else {
#endif
#if ENABLED(PIDTEMPBED)
if (code_seen('P')) bedKp = code_value();
if (code_seen('I')) bedKi = scalePID_i(code_value());
if (code_seen('D')) bedKd = scalePID_d(code_value());
......@@ -6704,12 +6774,36 @@ inline void gcode_M226() {
ECHO_SMV(OK, "p:", bedKp);
ECHO_MV(" i:", unscalePID_i(bedKi));
ECHO_EMV(" d:", unscalePID_d(bedKd));
#endif
#if ENABLED(PIDTEMPCOOLER) && ENABLED(PIDTEMPBED)
}
#endif
#endif // PIDTEMPBED
#if ENABLED(PIDTEMPCHAMBER)
// M305: Set chamber PID parameters P I and D
inline void gcode_M305() {
if (code_seen('P')) chamberKp = code_value();
if (code_seen('I')) chamberKi = scalePID_i(code_value());
if (code_seen('D')) chamberKd = scalePID_d(code_value());
updatePID();
ECHO_SMV(OK, "p:", chamberKp);
ECHO_MV(" i:", unscalePID_i(chamberKi));
ECHO_EMV(" d:", unscalePID_d(chamberKd));
}
#endif // PIDTEMPBED || PIDTEMPCOOLER
#endif // PIDTEMPCHAMBER
#if ENABLED(PIDTEMPCOOLER)
// M306: Set cooler PID parameters P I and D
inline void gcode_M306() {
if (code_seen('P')) coolerKp = code_value();
if (code_seen('I')) coolerKi = scalePID_i(code_value());
if (code_seen('D')) coolerKd = scalePID_d(code_value());
updatePID();
ECHO_SMV(OK, "p:", coolerKp);
ECHO_MV(" i:", unscalePID_i(coolerKi));
ECHO_EMV(" d:", unscalePID_d(coolerKd));
}
#endif // PIDTEMPCOOLER
#if HAS(MICROSTEPS)
// M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
......@@ -7385,6 +7479,7 @@ inline void gcode_M503() {
#else
#define RUNPLAN line_to_destination(FILAMENT_CHANGE_XY_FEEDRATE * 60);
#endif
KEEPALIVE_STATE(IN_HANDLER);
// Initial retract before move to filament change position
......@@ -7513,6 +7608,7 @@ inline void gcode_M503() {
#endif
lcd_filament_change_show_message(FILAMENT_CHANGE_MESSAGE_RESUME);
KEEPALIVE_STATE(IN_HANDLER);
// Set extruder to saved position
......@@ -7583,66 +7679,31 @@ inline void gcode_M503() {
}
#endif // DUAL_X_CARRIAGE
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
// M649 set laser options
inline void gcode_M649() {
// do this at the start so we can debug if needed!
if (code_seen('D') && IsRunning()) laser.diagnostics = (bool) code_value();
// Wait for the rest
//st_synchronize();
// st_synchronize();
if (code_seen('S') && IsRunning()) {
laser.intensity = (float) code_value();
laser.rasterlaserpower = laser.intensity;
}
if (code_seen('L') && IsRunning()) laser.duration = (unsigned long) labs(code_value());
if (code_seen('P') && IsRunning()) laser.ppm = (float) code_value();
if (code_seen('B') && IsRunning()) laser_set_mode((int) code_value());
if (code_seen('R') && IsRunning()) laser.raster_mm_per_pulse = ((float) code_value());
if (code_seen('F')) {
float next_feedrate = code_value();
if(next_feedrate > 0.0) feedrate = next_feedrate;
}
}
#if ENABLED(MUVE_Z_PEEL)
// M650 set peel distance
inline void gcode_M650() {
st_synchronize();
laser.peel_distance=2.0;
laser.peel_speed=2.0;
laser.peel_pause=0.0;
if(code_seen('D')) laser.peel_distance = (float) code_value();
if(code_seen('S')) laser.peel_speed = (float) code_value();
if(code_seen('P')) laser.peel_pause = (float) code_value();
}
// M651 run peel move
inline void gcode_M651() {
if(laser.peel_distance > 0) {
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS] + laser.peel_distance, destination[Z_AXIS], laser.peel_speed, active_extruder);
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS] + laser.peel_distance, destination[Z_AXIS] + laser.peel_distance, laser.peel_speed, active_extruder);
st_synchronize();
}
if(laser.peel_pause > 0) {
st_synchronize();
codenum = laser.peel_pause;
codenum += millis(); // keep track of when we started waiting
previous_millis_cmd = millis();
while(millis() < codenum ){
manage_temp_controller();
manage_inactivity();
lcd_update();
}
plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[Z_AXIS], 30, active_extruder);
st_synchronize();
}
}
#endif
#endif
#endif // LASERBEAM
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
//M666: Set Z probe offset
......@@ -8206,6 +8267,7 @@ void process_next_command() {
// The command's arguments (if any) start here, for sure!
current_command_args = cmd_ptr;
KEEPALIVE_STATE(IN_HANDLER);
// Handle a known G, M, or T
......@@ -8228,17 +8290,17 @@ void process_next_command() {
case 4:
gcode_G4(); break;
// G5 Bezier curve - from http://forums.reprap.org/read.php?147,93577
#if ENABLED(LASERBEAM)
#if ENABLED(G5_BEZIER)
case 5:
case 5: // G5: Bezier curve - from http://forums.reprap.org/read.php?147,93577
gcode_G5(); break;
#endif
// G7 Execute laser raster line
#if ENABLED(LASER) && ENABLED(LASER_RASTER)
case 7:
#if ENABLED(LASER_RASTER)
case 7: // G7: Execute laser raster line
gcode_G7(); break;
#endif
#endif
#if ENABLED(FWRETRACT)
case 10: // G10: retract
......@@ -8290,14 +8352,13 @@ void process_next_command() {
gcode_M0_M1(); break;
#endif //ULTIPANEL
#if ENABLED(LASERBEAM) || (ENABLED(LASER) && ENABLED(LASER_FIRE_SPINDLE))
#if ENABLED(LASERBEAM) && ENABLED(LASER_FIRE_SPINDLE)
case 3: // M03 S - Setting laser beam
gcode_M3(); break;
case 4: // M04 - Turn on laser beam
gcode_M4(); break;
gcode_M3_M4(); break;
case 5: // M05 - Turn off laser beam
gcode_M5(); break;
#endif //LASERBEAM
#endif // LASERBEAM
case 11: // M11 - Start/Stop printing serial mode
gcode_M11(); break;
......@@ -8469,8 +8530,20 @@ void process_next_command() {
#endif // HAS(HEATER_2)
#endif // BARICUDA
case 140: // M140 Set bed or cooler temp
#if HAS(TEMP_BED)
case 140: // M140 - Set bed temp
gcode_M140(); break;
#endif
#if HAS(TEMP_CHAMBER)
case 141: // M141 - Set chamber temp
gcode_M141(); break;
#endif
#if HAS(TEMP_COOLER)
case 142: // M142 - Set cooler temp
gcode_M142(); break;
#endif
#if ENABLED(BLINKM)
case 150: // M150
......@@ -8488,10 +8561,20 @@ void process_next_command() {
gcode_M165(); break;
#endif
#if HAS(TEMP_BED) || HAS(TEMP_COOLER)
case 190: // M190 - Wait for bed heater or for cooler to reach target.
#if HAS(TEMP_BED)
case 190: // M190 - Wait for bed heater to reach target.
gcode_M190(); break;
#endif //TEMP_BED || TEMP_COOLER
#endif // TEMP_BED
#if HAS(TEMP_CHAMBER)
case 191: // M191 - Wait for chamber heater to reach target.
gcode_M191(); break;
#endif
#if HAS(TEMP_COOLER)
case 192: // M192 - Wait for chamber heater to reach target.
gcode_M192(); break;
#endif
case 200: // M200 D<millimetres> set filament diameter and set E axis units to cubic millimetres (use S0 to set back to millimeters).
gcode_M200(); break;
......@@ -8566,11 +8649,21 @@ void process_next_command() {
gcode_M303(); break;
#endif
#if ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCOOLER)
case 304: // M304
#if ENABLED(PIDTEMPBED)
case 304: // M304 - Set Bed PID
gcode_M304(); break;
#endif // PIDTEMPBED
#if ENABLED(PIDTEMPCHAMBER)
case 305: // M305 - Set Chamber PID
gcode_M305(); break;
#endif // PIDTEMPCHAMBER
#if ENABLED(PIDTEMPCOOLER)
case 306: // M306 - Set Cooler PID
gcode_M306(); break;
#endif // PIDTEMPCOOLER
#if HAS(MICROSTEPS)
case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
gcode_M350(); break;
......@@ -8659,19 +8752,9 @@ void process_next_command() {
gcode_M605(); break;
#endif
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
case 649: // M649 set laser options
gcode_M649(); break;
#if ENABLED(MUVE_Z_PEEL)
case 650:
gcode_M650(); break;
case 651:
gcode_M651(); break;
#endif
#endif
#if ENABLED(AUTO_BED_LEVELING_FEATURE) || MECH(DELTA)
......@@ -8753,7 +8836,7 @@ void clamp_to_software_endstops(float target[3]) {
if (SOFTWARE_MIN_ENDSTOPS && software_endstops) {
NOLESS(target[X_AXIS], sw_endstop_min[X_AXIS]);
NOLESS(target[Y_AXIS], sw_endstop_min[Y_AXIS]);
#if !ENABLED(LASER)
#if !ENABLED(LASERBEAM)
float negative_z_offset = 0;
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
if (zprobe_zoffset < 0) negative_z_offset += zprobe_zoffset;
......@@ -8770,11 +8853,10 @@ void clamp_to_software_endstops(float target[3]) {
if (SOFTWARE_MAX_ENDSTOPS && software_endstops) {
NOMORE(target[X_AXIS], sw_endstop_max[X_AXIS]);
NOMORE(target[Y_AXIS], sw_endstop_max[Y_AXIS]);
#if !ENABLED(LASER)
#if !ENABLED(LASERBEAM)
NOMORE(target[Z_AXIS], sw_endstop_max[Z_AXIS]);
#endif
}
}
/**
......@@ -8940,25 +9022,21 @@ static void report_current_position() {
#if MECH(CARTESIAN) || MECH(COREXY) || MECH(COREYX) || MECH(COREXZ) || MECH(COREZX)
inline bool prepare_move_cartesian() {
#if ENABLED(LASER) && ENABLED(LASER_FIRE_E)
#if ENABLED(LASERBEAM) && ENABLED(LASER_FIRE_E)
if (current_position[E_AXIS] != destination[E_AXIS] && ((current_position[X_AXIS] != destination [X_AXIS]) || (current_position[Y_AXIS] != destination [Y_AXIS]))){
laser.status = LASER_ON;
laser.fired = LASER_FIRE_E;
}
if (current_position[E_AXIS] == destination[E_AXIS] && laser.fired == LASER_FIRE_E){
if (current_position[E_AXIS] == destination[E_AXIS] && laser.fired == LASER_FIRE_E)
laser.status = LASER_OFF;
}
#endif
// Do not use feedrate_multiplier for E or Z only moves
if (current_position[X_AXIS] == destination[X_AXIS] && current_position[Y_AXIS] == destination[Y_AXIS]) {
if (current_position[X_AXIS] == destination[X_AXIS] && current_position[Y_AXIS] == destination[Y_AXIS])
line_to_destination();
#if ENABLED(LASER) && ENABLED(MUVE_Z_PEEL)
current_position[E_AXIS] = current_position[Z_AXIS];
#endif
}
else {
else
line_to_destination(feedrate * feedrate_multiplier / 100.0);
}
return true;
}
......@@ -9345,7 +9423,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
#if DISABLE_E == true
disable_e();
#endif
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
if (laser.time / 60000 > 0) {
laser.lifetime += laser.time / 60000; // convert to minutes
laser.time = 0;
......@@ -9540,7 +9618,7 @@ void kill(const char* lcd_msg) {
HAL::resetHardware();
#endif
#if ENABLED(FLOWMETER_SENSOR) && ENABLED(MINFLOW_PROTECTION)
flow_firstread=false;
flow_firstread = false;
#endif
#if ENABLED(ULTRA_LCD)
......@@ -9552,13 +9630,12 @@ void kill(const char* lcd_msg) {
disable_all_coolers();
disable_all_steppers();
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
laser_init();
#endif
#if ENABLED(LASER_PERIPHERALS)
laser_peripherals_off();
#endif
#endif
#if HAS(POWER_SWITCH)
SET_INPUT(PS_ON_PIN);
......@@ -9658,15 +9735,17 @@ void stop() {
#if ENABLED(FLOWMETER_SENSOR) && ENABLED(MINFLOW_PROTECTION)
flow_firstread=false;
#endif
disable_all_heaters();
disable_all_coolers();
#ifdef LASER
#if ENABLED(LASERBEAM)
if (laser.diagnostics) ECHO_LM(INFO, "Laser set to off, stop() called");
laser_extinguish();
#endif
#ifdef LASER_PERIPHERALS
#if ENABLED(LASER_PERIPHERALS)
laser_peripherals_off();
#endif
#endif
if (IsRunning()) {
Running = false;
......
......@@ -117,8 +117,7 @@ inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); }
extern void delay_ms(millis_t ms);
#if ENABLED(FAST_PWM_FAN) || ENABLED(FAST_PWM_COOLER)
void setPwmFrequency(uint8_t pin, int val);
void setPwmFrequency(uint8_t pin, uint8_t val);
#endif
extern float homing_feedrate[];
......@@ -237,10 +236,6 @@ extern int fanSpeed;
extern bool allow_lengthy_extrude_once; // for load/unload
#endif
#if ENABLED(LASERBEAM)
extern int laser_ttl_modulation;
#endif
// Print job timer
extern PrintCounter print_job_counter;
......@@ -262,12 +257,16 @@ extern uint8_t active_driver;
void print_heaterstates();
#endif
#if HAS(TEMP_CHAMBER)
void print_chamberstate();
#endif
#if HAS(TEMP_COOLER)
void print_coolerstates();
void print_coolerstate();
#endif
#if ENABLED(FLOWMETER_SENSOR)
void print_flowratestates();
void print_flowratestate();
#endif
#if ENABLED(FIRMWARE_TEST)
......
/*
* Copyright (c) 2013 Adam Rudd.
* See LICENSE for more information
*/
#ifndef _BASE64_H
#define _BASE64_H
/* b64_alphabet:
* Description: Base64 alphabet table, a mapping between integers
* and base64 digits
* Notes: This is an extern here but is defined in Base64.c
*/
extern const char b64_alphabet[];
/* base64_encode:
* Description:
* Encode a string of characters as base64
* Parameters:
* output: the output buffer for the encoding, stores the encoded string
* input: the input buffer for the encoding, stores the binary to be encoded
* inputLen: the length of the input buffer, in bytes
* Return value:
* Returns the length of the encoded string
* Requirements:
* 1. output must not be null or empty
* 2. input must not be null
* 3. inputLen must be greater than or equal to 0
*/
int base64_encode(char *output, char *input, int inputLen);
/* base64_decode:
* Description:
* Decode a base64 encoded string into bytes
* Parameters:
* output: the output buffer for the decoding,
* stores the decoded binary
* input: the input buffer for the decoding,
* stores the base64 string to be decoded
* inputLen: the length of the input buffer, in bytes
* Return value:
* Returns the length of the decoded string
* Requirements:
* 1. output must not be null or empty
* 2. input must not be null
* 3. inputLen must be greater than or equal to 0
*/
int base64_decode(unsigned char *output, char *input, int inputLen);
/* base64_enc_len:
* Description:
* Returns the length of a base64 encoded string whose decoded
* form is inputLen bytes long
* Parameters:
* inputLen: the length of the decoded string
* Return value:
* The length of a base64 encoded string whose decoded form
* is inputLen bytes long
* Requirements:
* None
*/
int base64_enc_len(int inputLen);
/* base64_dec_len:
* Description:
* Returns the length of the decoded form of a
* base64 encoded string
* Parameters:
* input: the base64 encoded string to be measured
* inputLen: the length of the base64 encoded string
* Return value:
* Returns the length of the decoded form of a
* base64 encoded string
* Requirements:
* 1. input must not be null
* 2. input must be greater than or equal to zero
*/
int base64_dec_len(char *input, int inputLen);
#endif // _BASE64_H
......@@ -13,7 +13,9 @@
#if MB(RAMPS_FD_V1)
#define RAMPS_FD_V1
#define INVERTED_HEATER_PINS
#define INVERTED_BED_PINS
#define INVERTED_BED_PIN
#define INVERTED_CHAMBER_PIN
#define INVERTED_COOLER_PIN
// No EEPROM
// Use 4k7 thermistor tables
#else
......
......@@ -13,7 +13,9 @@
#if MB(RAMPS_FD_V1)
#define RAMPS_FD_V1
#define INVERTED_HEATER_PINS
#define INVERTED_BED_PINS
#define INVERTED_BED_PIN
#define INVERTED_CHAMBER_PIN
#define INVERTED_COOLER_PIN
// No EEPROM
// Use 4k7 thermistor tables
#else
......
......@@ -605,6 +605,16 @@
#define BED_USES_THERMISTOR
#endif
#if TEMP_SENSOR_CHAMBER == -1
#define CHAMBER_USES_AD595
#elif TEMP_SENSOR_CHAMBER == 0
#undef CHAMBER_MINTEMP
#undef CHAMBER_MAXTEMP
#elif TEMP_SENSOR_CHAMBER > 0
#define THERMISTORCHAMBER TEMP_SENSOR_CHAMBER
#define CHAMBER_USES_THERMISTOR
#endif
#if TEMP_SENSOR_COOLER == -1
#define COOLER_USES_AD595
#elif TEMP_SENSOR_COOLER == 0
......@@ -615,19 +625,20 @@
#define COOLER_USES_THERMISTOR
#endif
#if !ENABLED(COOLER)
#if HASNT(COOLER)
#if ENABLED(PIDTEMPCOOLER)
#undef PIDTEMPCOOLER
#endif
#endif
#define HEATER_USES_AD595 (ENABLED(HEATER_0_USES_AD595) || ENABLED(HEATER_1_USES_AD595) || ENABLED(HEATER_2_USES_AD595) || ENABLED(HEATER_3_USES_AD595))
/**
* Flags for PID handling
*/
#define HAS_PID_HEATING (ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED))
#define HAS_PID_COOLING (ENABLED(PIDTEMPCOOLER))
#define HAS_PID_FOR_BOTH (ENABLED(PIDTEMP) && ENABLED(PIDTEMPBED))
#define HAS_PID_COOLING (ENABLED(PIDTEMPCOOLER))
/**
* ARRAY_BY_EXTRUDERS based on EXTRUDERS
......@@ -677,13 +688,15 @@
#define HAS_TEMP_2 (PIN_EXISTS(TEMP_2) && TEMP_SENSOR_2 != 0)
#define HAS_TEMP_3 (PIN_EXISTS(TEMP_3) && TEMP_SENSOR_3 != 0)
#define HAS_TEMP_BED (PIN_EXISTS(TEMP_BED) && TEMP_SENSOR_BED != 0)
#define HAS_TEMP_CHAMBER (PIN_EXISTS(TEMP_CHAMBER) && TEMP_SENSOR_CHAMBER != 0)
#define HAS_TEMP_COOLER (PIN_EXISTS(TEMP_COOLER) && TEMP_SENSOR_COOLER != 0)
#define HAS_HEATER_0 (PIN_EXISTS(HEATER_0))
#define HAS_HEATER_1 (PIN_EXISTS(HEATER_1))
#define HAS_HEATER_2 (PIN_EXISTS(HEATER_2))
#define HAS_HEATER_3 (PIN_EXISTS(HEATER_3))
#define HAS_HEATER_BED (PIN_EXISTS(HEATER_BED))
#define HAS_COOLER_DEV (PIN_EXISTS(COOLER))
#define HAS_HEATER_CHAMBER (PIN_EXISTS(HEATER_CHAMBER))
#define HAS_COOLER (PIN_EXISTS(COOLER))
#define HAS_AUTO_FAN_0 (ENABLED(EXTRUDER_AUTO_FAN) && PIN_EXISTS(EXTRUDER_0_AUTO_FAN))
#define HAS_AUTO_FAN_1 (ENABLED(EXTRUDER_AUTO_FAN) && PIN_EXISTS(EXTRUDER_1_AUTO_FAN))
#define HAS_AUTO_FAN_2 (ENABLED(EXTRUDER_AUTO_FAN) && PIN_EXISTS(EXTRUDER_2_AUTO_FAN))
......@@ -808,14 +821,21 @@
#define WRITE_HEATER_0(v) WRITE_HEATER_0P(v)
#endif
#if HAS(HEATER_BED)
#if ENABLED(INVERTED_BED_PINS)
#if ENABLED(INVERTED_BED_PIN)
#define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN,!v)
#else
#define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN,v)
#endif
#endif
#if HAS(COOLER_DEV)
#if ENABLED(INVERTED_COOLER_PINS)
#if HAS(HEATER_CHAMBER)
#if ENABLED(INVERTED_CHAMBER_PIN)
#define WRITE_HEATER_CHAMBER(v) WRITE(HEATER_CHAMBER_PIN,!v)
#else
#define WRITE_HEATER_CHAMBER(v) WRITE(HEATER_CHAMBER_PIN,v)
#endif
#endif
#if HAS(COOLER)
#if ENABLED(INVERTED_COOLER_PIN)
#define WRITE_COOLER(v) WRITE(COOLER_PIN,!v)
#else
#define WRITE_COOLER(v) WRITE(COOLER_PIN,v)
......
/*
flowmeter.cpp - Flowmeter control library for Arduino - Version 1
Copyright (c) 2016 Franco (nextime) Lanza. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 3 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "../../base.h"
#include <Arduino.h>
#if ENABLED(FLOWMETER_SENSOR)
volatile int flowrate_pulsecount;
float flowrate;
static millis_t flowmeter_timer = 0;
static millis_t lastflow = 0;
void flowrate_pulsecounter();
void flow_init() {
flowrate = 0;
flowrate_pulsecount = 0;
pinMode(FLOWMETER_PIN, INPUT);
attachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN), flowrate_pulsecounter, FALLING);
}
void flowrate_manage() {
millis_t now;
now = millis();
if(ELAPSED(now, flowmeter_timer)) {
detachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN));
flowrate = (float)(((1000.0 / (float)((float)now - (float)lastflow)) * (float)flowrate_pulsecount) / (float)FLOWMETER_CALIBRATION);
#if ENABLED(FLOWMETER_DEBUG)
ECHO_M(" FLOWMETER DEBUG ");
ECHO_MV(" flowrate:", flowrate);
ECHO_MV(" flowrate_pulsecount:", flowrate_pulsecount);
ECHO_MV(" CALIBRATION:", FLOWMETER_CALIBRATION);
ECHO_E;
#endif
flowmeter_timer = now + 1000UL;
lastflow = now;
flowrate_pulsecount = 0;
attachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN), flowrate_pulsecounter, FALLING);
}
}
float get_flowrate() {
return flowrate;
}
void flowrate_pulsecounter()
{
// Increment the pulse counter
flowrate_pulsecount++;
}
#endif // FLOWMETER_SENSOR
/*
flowmeter.h - Flowmeter control library for Arduino - Version 1
Copyright (c) 2016 Franco (nextime) Lanza. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 3 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef FLOWMETER_H
#define FLOWMETER_H
#define FLOWMETER_CALIBRATION (FLOWMETER_MAXFREQ/FLOWMETER_MAXFLOW)
#if ENABLED(FLOWMETER_SENSOR)
void flowrate_manage();
void flow_init();
float get_flowrate();
#endif
#endif // FLOWMETER_H
......@@ -198,9 +198,10 @@
#define SERIAL_PID_DEBUG_CTERM " cTerm "
#define SERIAL_INVALID_EXTRUDER_NUM " - Invalid extruder number !"
#define SERIAL_HEATER_BED "bed"
#define SERIAL_STOPPED_HEATER ", system stopped! Heater_ID: "
#define SERIAL_STOPPED_COOLER "system stopped! Cooler"
#define SERIAL_STOPPED_BED ", system stopped! Bed"
#define SERIAL_STOPPED_CHAMBER ", system stopped! Chamber"
#define SERIAL_STOPPED_COOLER ", system stopped! Cooler"
#define SERIAL_REDUNDANCY "Heater switched off. Temperature difference between temp sensors is too high !"
#define SERIAL_T_HEATING_FAILED "Heating failed"
#define SERIAL_T_THERMAL_RUNAWAY "Thermal Runaway"
......
......@@ -184,6 +184,8 @@
#define MSG_ERR_MINTEMP "MINTEMP ERROR"
#define MSG_ERR_MAXTEMP_BED "MAXTEMP BED ERROR"
#define MSG_ERR_MINTEMP_BED "MINTEMP BED ERROR"
#define MSG_ERR_MAXTEMP_CHAMBER "MAXTEMP CHAMBER ERROR"
#define MSG_ERR_MINTEMP_CHAMBER "MINTEMP CHAMBER ERROR"
#define MSG_ERR_MAXTEMP_COOLER "MAXTEMP COOLER ERROR"
#define MSG_ERR_MINTEMP_COOLER "MINTEMP COOLER ERROR"
#define MSG_END_DAY "days"
......
......@@ -181,6 +181,8 @@
#define MSG_ERR_MINTEMP "Err: TEMP MINIMA"
#define MSG_ERR_MAXTEMP_BED "Err: TEMP MASSIMA PIATTO"
#define MSG_ERR_MINTEMP_BED "Err: TEMP MINIMA PIATTO"
#define MSG_ERR_MAXTEMP_CHAMBER "MAXTEMP CHAMBER ERROR"
#define MSG_ERR_MINTEMP_CHAMBER "MINTEMP CHAMBER ERROR"
#define MSG_ERR_MAXTEMP_COOLER "MAXTEMP COOLER ERROR"
#define MSG_ERR_MINTEMP_COOLER "MINTEMP COOLER ERROR"
#define MSG_END_DAY "giorni"
......@@ -246,7 +248,6 @@
#define MSG_COOLER_COOLING "Raffreddamento..."
#define MSG_COOLER_DONE "Raffreddamento finito."
// Extra
#define MSG_LASER "Laser Preset"
#define MSG_CONFIG "Configurazione"
......
#include "Base64.h"
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#include "base64.h"
const char b64_alphabet[] = "ABCDEFGHIJKLMNOPQRSTUVWXYZ"
"abcdefghijklmnopqrstuvwxyz"
......@@ -53,7 +75,6 @@ int base64_decode(unsigned char * output, char * input, int inputLen) {
unsigned char a3[3];
unsigned char a4[4];
while (inputLen--) {
if(*input == '=') {
break;
......
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* Copyright (c) 2013 Adam Rudd.
* See LICENSE for more information
*/
#ifndef _BASE64_H
#define _BASE64_H
/* b64_alphabet:
* Description: Base64 alphabet table, a mapping between integers
* and base64 digits
* Notes: This is an extern here but is defined in Base64.c
*/
extern const char b64_alphabet[];
/* base64_encode:
* Description:
* Encode a string of characters as base64
* Parameters:
* output: the output buffer for the encoding, stores the encoded string
* input: the input buffer for the encoding, stores the binary to be encoded
* inputLen: the length of the input buffer, in bytes
* Return value:
* Returns the length of the encoded string
* Requirements:
* 1. output must not be null or empty
* 2. input must not be null
* 3. inputLen must be greater than or equal to 0
*/
int base64_encode(char *output, char *input, int inputLen);
/* base64_decode:
* Description:
* Decode a base64 encoded string into bytes
* Parameters:
* output: the output buffer for the decoding,
* stores the decoded binary
* input: the input buffer for the decoding,
* stores the base64 string to be decoded
* inputLen: the length of the input buffer, in bytes
* Return value:
* Returns the length of the decoded string
* Requirements:
* 1. output must not be null or empty
* 2. input must not be null
* 3. inputLen must be greater than or equal to 0
*/
int base64_decode(unsigned char *output, char *input, int inputLen);
/* base64_enc_len:
* Description:
* Returns the length of a base64 encoded string whose decoded
* form is inputLen bytes long
* Parameters:
* inputLen: the length of the decoded string
* Return value:
* The length of a base64 encoded string whose decoded form
* is inputLen bytes long
* Requirements:
* None
*/
int base64_enc_len(int inputLen);
/* base64_dec_len:
* Description:
* Returns the length of the decoded form of a
* base64 encoded string
* Parameters:
* input: the base64 encoded string to be measured
* inputLen: the length of the base64 encoded string
* Return value:
* Returns the length of the decoded form of a
* base64 encoded string
* Requirements:
* 1. input must not be null
* 2. input must be greater than or equal to zero
*/
int base64_dec_len(char *input, int inputLen);
#endif // _BASE64_H
/*
laser.cpp - Laser control library for Arduino using 16 bit timers- Version 1
Copyright (c) 2013 Timothy Schmidt. All right reserved.
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 3 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/**
* laser.cpp - Laser control library for Arduino using 16 bit timers- Version 1
* Copyright (c) 2013 Timothy Schmidt. All right reserved.
* Copyright (c) 2016 Franco (nextime) Lanza
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "../../base.h"
#include <avr/interrupt.h>
#include <Arduino.h>
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
laser_t laser;
laser_t laser;
#if ENABLED(LASER_PULSE_METHOD)
#define pulsebit(x) (1 << x)
#ifndef PE3 // Undef'd in fastio.h.
#define PE3 3
#endif
#endif
#if ENABLED(LASER_PULSE_METHOD)
#define pulsebit(x) (1 << x)
#ifndef PE3 // Undef'd in fastio.h.
#define PE3 3
#endif
#endif
void timer3_init(int pin) {
void timer3_init(int pin) {
#if ENABLED(LASER_PULSE_METHOD)
TCCR3A = 0; // clear control register A
TCCR3B = pulsebit(WGM33); // set mode as phase and frequency correct pwm, stop the timer
......@@ -95,7 +118,9 @@ void timer3_init(int pin) {
TCCR4A = 0;
TCCR4B = pulsebit(WGM42); // CTC
TIMSK4 |= pulsebit(OCIE4A); // Enable interrupt on OCR4A
#else
pinMode(pin, OUTPUT);
analogWrite(pin, 1); // let Arduino setup do it's thing to the PWM pin
......@@ -111,20 +136,19 @@ void timer3_init(int pin) {
ICR3 = labs(F_CPU / LASER_PWM); // set new PWM period
TCCR3B |= 0x01; // start the timer with proper prescaler value
interrupts();
#endif
}
}
#if ENABLED(LASER_PULSE_METHOD)
ISR(TIMER4_COMPA_vect)
{
#if ENABLED(LASER_PULSE_METHOD)
ISR(TIMER4_COMPA_vect) {
OCR3A = 0; // 0 Duty cycle
// Stop pulse shutdown timer
TCCR4B &= ~(pulsebit(CS40) | pulsebit(CS41) | pulsebit(CS42)); // Stop timer.
}
void laser_pulse(uint32_t ulValue, unsigned long usec)
{
void laser_pulse(uint32_t ulValue, unsigned long usec) {
OCR3A = ulValue; // Duty cycle of pulse
// Start timer4 to end pulse
......@@ -133,7 +157,9 @@ void timer3_init(int pin) {
TCCR4B |= pulsebit(CS41); // Start timer
TIFR4 = pulsebit(OCF4A); // Clear any pending interrupt
}
#else // LASER_PULSE_METHOD
#else // LASER_PULSE_METHOD
void timer4_init(int pin) {
pinMode(pin, OUTPUT);
analogWrite(pin, 1); // let Arduino setup do it's thing to the PWM pin
......@@ -151,29 +177,28 @@ void timer3_init(int pin) {
TCCR4B |= 0x01; // start the timer with proper prescaler value
interrupts();
}
#endif // LASER_PULSE_METHOD
void laser_init()
{
#endif // LASER_PULSE_METHOD
void laser_init() {
#if ENABLED(LASER_PULSE_METHOD)
// Initialize timers for laser intensity control
// ONLY laser_firing on pin 5. Can't use pin 6 for output, used by timer4.
timer3_init(LASER_FIRING_PIN);
timer3_init(LASER_PWR_PIN);
#else
// Initialize timers for laser intensity control
#if LASER_CONTROL == 1
if (LASER_FIRING_PIN == 2 || LASER_FIRING_PIN == 3 || LASER_FIRING_PIN == 5) timer3_init(LASER_FIRING_PIN);
if (LASER_FIRING_PIN == 6 || LASER_FIRING_PIN == 7 || LASER_FIRING_PIN == 8) timer4_init(LASER_FIRING_PIN);
if (LASER_PWR_PIN == 2 || LASER_PWR_PIN == 3 || LASER_PWR_PIN == 5) timer3_init(LASER_PWR_PIN);
if (LASER_PWR_PIN == 6 || LASER_PWR_PIN == 7 || LASER_PWR_PIN == 8) timer4_init(LASER_PWR_PIN);
#endif
#if LASER_CONTROL == 2
if (LASER_INTENSITY_PIN == 2 || LASER_INTENSITY_PIN == 3 || LASER_INTENSITY_PIN == 5) timer3_init(LASER_INTENSITY_PIN);
if (LASER_INTENSITY_PIN == 6 || LASER_INTENSITY_PIN == 7 || LASER_INTENSITY_PIN == 8) timer4_init(LASER_INTENSITY_PIN);
if (LASER_TTL_PIN == 2 || LASER_TTL_PIN == 3 || LASER_TTL_PIN == 5) timer3_init(LASER_TTL_PIN);
if (LASER_TTL_PIN == 6 || LASER_TTL_PIN == 7 || LASER_TTL_PIN == 8) timer4_init(LASER_TTL_PIN);
#endif
#endif // LASER_PULSE_METHOD
#ifdef LASER_PERIPHERALS
#if ENABLED(LASER_PERIPHERALS)
digitalWrite(LASER_PERIPHERALS_PIN, HIGH); // Laser peripherals are active LOW, so preset the pin
pinMode(LASER_PERIPHERALS_PIN, OUTPUT);
......@@ -181,8 +206,8 @@ void laser_init()
pinMode(LASER_PERIPHERALS_STATUS_PIN, INPUT);
#endif // LASER_PERIPHERALS
digitalWrite(LASER_FIRING_PIN, LASER_UNARM); // Laser FIRING is active LOW, so preset the pin
pinMode(LASER_FIRING_PIN, OUTPUT);
digitalWrite(LASER_PWR_PIN, LASER_UNARM); // Laser FIRING is active LOW, so preset the pin
pinMode(LASER_PWR_PIN, OUTPUT);
// initialize state to some sane defaults
laser.intensity = 50.0;
......@@ -194,22 +219,19 @@ void laser_init()
laser.last_firing = 0;
laser.diagnostics = false;
laser.time = 0;
#ifdef LASER_RASTER
#if ENABLED(LASER_RASTER)
laser.raster_aspect_ratio = LASER_RASTER_ASPECT_RATIO;
laser.raster_mm_per_pulse = LASER_RASTER_MM_PER_PULSE;
laser.raster_direction = 1;
#endif // LASER_RASTER
#ifdef MUVE_Z_PEEL
laser.peel_distance = 2.0;
laser.peel_speed = 2.0;
laser.peel_pause = 0.0;
#endif // MUVE_Z_PEEL
#if !ENABLED(LASER_PULSE_METHOD)
laser_extinguish();
#endif
}
void laser_fire(float intensity = 100.0){
}
void laser_fire(float intensity = 100.0){
laser.firing = LASER_ON;
laser.last_firing = micros(); // microseconds of last laser firing
if (intensity > 100.0) intensity = 100.0; // restrict intensity between 0 and 100
......@@ -229,26 +251,27 @@ void laser_fire(float intensity = 100.0){
#endif
#if (!ENABLED(LASER_PULSE_METHOD))
pinMode(LASER_FIRING_PIN, OUTPUT);
pinMode(LASER_PWR_PIN, OUTPUT);
#endif
#if LASER_CONTROL == 1
#if ENABLED(LASER_PULSE_METHOD)
OCR3A = labs((intensity / 100.0)*(F_CPU / LASER_PWM / 2));
OCR3A = labs((intensity / 100.0) * (F_CPU / LASER_PWM / 2));
#else
analogWrite(LASER_FIRING_PIN, labs((intensity / 100.0)*(F_CPU / LASER_PWM)));
analogWrite(LASER_PWR_PIN, labs((intensity / 100.0) * (F_CPU / LASER_PWM)));
#endif
#endif
#if LASER_CONTROL == 2
analogWrite(LASER_INTENSITY_PIN, labs((intensity / 100.0)*(F_CPU / LASER_PWM)));
digitalWrite(LASER_FIRING_PIN, LASER_ARM);
analogWrite(LASER_TTL_PIN, labs((intensity / 100.0) * (F_CPU / LASER_PWM)));
digitalWrite(LASER_PWR_PIN, LASER_ARM);
#endif
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(INFO, "Laser fired");
}
}
void laser_extinguish(){
void laser_extinguish() {
if (laser.firing == LASER_ON) {
laser.firing = LASER_OFF;
......@@ -256,18 +279,18 @@ void laser_extinguish(){
OCR3A = 0; // Zero duty cycle = OFF
#else
// Engage the pullup resistor for TTL laser controllers which don't turn off entirely without it.
digitalWrite(LASER_FIRING_PIN, LASER_UNARM);
digitalWrite(LASER_PWR_PIN, LASER_UNARM);
#endif
laser.time += millis() - (laser.last_firing / 1000);
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(INFO, "Laser extinguished");
}
}
}
void laser_set_mode(int mode){
switch(mode){
void laser_set_mode(int mode) {
switch(mode) {
case 0:
laser.mode = CONTINUOUS;
return;
......@@ -278,40 +301,40 @@ void laser_set_mode(int mode){
laser.mode = RASTER;
return;
}
}
#ifdef LASER_PERIPHERALS
bool laser_peripherals_ok(){
return !digitalRead(LASER_PERIPHERALS_STATUS_PIN);
}
void laser_peripherals_on(){
}
#if ENABLED(LASER_PERIPHERALS)
bool laser_peripherals_ok() { return !digitalRead(LASER_PERIPHERALS_STATUS_PIN); }
void laser_peripherals_on() {
digitalWrite(LASER_PERIPHERALS_PIN, LOW);
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(INFO, "Laser Peripherals Enabled");
}
}
void laser_peripherals_off(){
void laser_peripherals_off() {
if (!digitalRead(LASER_PERIPHERALS_STATUS_PIN)) {
digitalWrite(LASER_PERIPHERALS_PIN, HIGH);
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(INFO, "Laser Peripherals Disabled");
}
}
}
void laser_wait_for_peripherals() {
void laser_wait_for_peripherals() {
unsigned long timeout = millis() + LASER_PERIPHERALS_TIMEOUT;
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(INFO, "Waiting for peripheral control board signal...");
}
while(!laser_peripherals_ok()) {
if (millis() > timeout) {
if (laser.diagnostics) {
if (laser.diagnostics)
ECHO_LM(ER, "Peripheral control board failed to respond");
}
Stop();
break;
}
}
}
#endif // LASER_PERIPHERALS
}
#endif // LASER_PERIPHERALS
#endif // LASER
#endif // LASERBEAM
/*
laser.h - Laser cutter control library for Arduino using 16 bit timers- Version 1
Copyright (c) 2013 Timothy Schmidt. All right reserved.
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 3 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
/**
* laser.cpp - Laser control library for Arduino using 16 bit timers- Version 1
* Copyright (c) 2013 Timothy Schmidt. All right reserved.
* Copyright (c) 2016 Franco (nextime) Lanza
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef LASER_H
#define LASER_H
#define LASER_H
#include <inttypes.h>
#include "../../base.h"
#include <inttypes.h>
// split into planned and status
typedef struct {
// split into planned and status
typedef struct {
int fired; // method used to ask the laser to fire - LASER_FIRE_G1, LASER_FIRE_SPINDLE, LASER_FIRE_E, etc
float intensity; // Laser firing instensity 0.0 - 100.0
float ppm; // pulses per millimeter, for pulsed firing mode
......@@ -37,7 +59,7 @@ typedef struct {
bool diagnostics; // Verbose debugging output over serial
unsigned int time; // temporary counter to limit eeprom writes
unsigned int lifetime; // laser lifetime firing counter in minutes
#ifdef LASER_RASTER
#if ENABLED(LASER_RASTER)
unsigned char raster_data[LASER_MAX_RASTER_LINE];
unsigned char rasterlaserpower;
......@@ -47,44 +69,39 @@ typedef struct {
int raster_num_pixels;
bool raster_direction;
#endif // LASER_RASTER
#ifdef MUVE_Z_PEEL
float peel_distance;
float peel_speed;
float peel_pause;
#endif // MUVE_Z_PEEL
} laser_t;
} laser_t;
extern laser_t laser;
extern laser_t laser;
void laser_init();
void laser_fire(float intensity);
#if ENABLED(LASER_PULSE_METHOD)
void laser_init();
void laser_fire(float intensity);
#if ENABLED(LASER_PULSE_METHOD)
void laser_pulse(uint32_t ulValue, unsigned long usec);
#endif
void laser_extinguish();
void laser_update_lifetime();
void laser_set_mode(int mode);
#ifdef LASER_PERIPHERALS
#endif
void laser_extinguish();
void laser_update_lifetime();
void laser_set_mode(int mode);
#if ENABLED(LASER_PERIPHERALS)
bool laser_peripherals_ok();
void laser_peripherals_on();
void laser_peripherals_off();
void laser_wait_for_peripherals();
#endif // LASER_PERIPHERALS
#endif // LASER_PERIPHERALS
#ifdef HIGH_TO_FIRE // Some cutters fire on high, some on low.
#ifdef HIGH_TO_FIRE // Some cutters fire on high, some on low.
#define LASER_ARM HIGH
#define LASER_UNARM LOW
#else
#else
#define LASER_ARM LOW
#define LASER_UNARM HIGH
#endif
#endif
// Laser constants
#define LASER_OFF 0
#define LASER_ON 1
// Laser constants
#define LASER_OFF 0
#define LASER_ON 1
#define CONTINUOUS 0
#define PULSED 1
#define RASTER 2
#define CONTINUOUS 0
#define PULSED 1
#define RASTER 2
#endif // LASER_H
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
#define LASERENABLE_HEIGHT 20
#define LASERENABLE_WIDTH 25
......
......@@ -67,8 +67,8 @@
#undef USE_BIG_EDIT_FONT
#endif
#if ENABLED(LASER)
#include "../laser/laserbitmaps.h"
#if ENABLED(LASERBEAM)
#include "../laser/laserbitmaps.h"
#endif
#if ENABLED(USE_SMALL_INFOFONT)
......@@ -374,7 +374,7 @@ static void lcd_implementation_status_screen() {
bool blink = lcd_blink();
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
#if ENABLED(LASER_PERIPHERALS)
if (laser_peripherals_ok()) {
u8g.drawBitmapP(29,4, LASERENABLE_BYTEWIDTH, LASERENABLE_HEIGHT, laserenable_bmp);
......@@ -474,7 +474,7 @@ static void lcd_implementation_status_screen() {
}
#endif
#if DISABLED(LASER)
#if DISABLED(LASERBEAM)
// Hotends
for (int i = 0; i < HOTENDS; i++) _draw_heater_status(6 + i * 25, i);
......@@ -482,8 +482,8 @@ static void lcd_implementation_status_screen() {
#if HOTENDS < 4 && HAS(TEMP_BED)
_draw_heater_status(81, -1);
#endif
#endif // !LASERBEAM
#endif // DISABLED LASER
// Fan
u8g.setPrintPos(104, 27);
#if HAS(FAN)
......
......@@ -88,7 +88,7 @@ char lcd_status_message[3 * (LCD_WIDTH) + 1] = WELCOME_MSG; // worst case is kan
#define LCD_Printpos(x, y) lcd.setCursor(x, y)
#endif
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
static void lcd_laser_focus_menu();
static void lcd_laser_menu();
static void lcd_laser_test_fire_menu();
......@@ -109,7 +109,6 @@ char lcd_status_message[3 * (LCD_WIDTH) + 1] = WELCOME_MSG; // worst case is kan
static void action_laser_test_warm();
static void action_laser_acc_on();
static void action_laser_acc_off();
#endif
// The main status screen
......@@ -127,7 +126,7 @@ static void lcd_status_screen();
static void lcd_move_menu();
static void lcd_control_menu();
static void lcd_stats_menu();
#if DISABLED(LASER)
#if DISABLED(LASERBEAM)
static void lcd_control_temperature_menu();
static void lcd_control_temperature_preheat_pla_settings_menu();
static void lcd_control_temperature_preheat_abs_settings_menu();
......@@ -135,7 +134,7 @@ static void lcd_status_screen();
#endif
static void lcd_control_motion_menu();
#if DISABLED(LASER)
#if DISABLED(LASERBEAM)
static void lcd_control_volumetric_menu();
#endif
......@@ -218,7 +217,7 @@ static void lcd_status_screen();
/**
* START_MENU generates the init code for a menu function
*/
#if ENABLED(BTN_BACK) && BTN_BACK > 0
#if ENABLED(BTN_BACK) && BTN_BACK > 0
#define START_MENU() do { \
ENCODER_DIRECTION_MENUS(); \
encoderRateMultiplierEnabled = false; \
......@@ -234,7 +233,7 @@ static void lcd_status_screen();
return; } \
for (uint8_t _drawLineNr = 0; _drawLineNr < LCD_HEIGHT; _drawLineNr++, _lineNr++) { \
_menuItemNr = 0;
#else
#else
#define START_MENU() do { \
ENCODER_DIRECTION_MENUS(); \
encoderRateMultiplierEnabled = false; \
......@@ -245,7 +244,7 @@ static void lcd_status_screen();
bool wasClicked = LCD_CLICKED, itemSelected; \
for (uint8_t _drawLineNr = 0; _drawLineNr < LCD_HEIGHT; _drawLineNr++, _lineNr++) { \
_menuItemNr = 0;
#endif
#endif
/**
* MENU_ITEM generates draw & handler code for a menu item, potentially calling:
......@@ -555,14 +554,21 @@ inline void line_to_current(AxisEnum axis) {
#if ENABLED(SDSUPPORT)
static void lcd_sdcard_pause() { card.pausePrint(); }
static void lcd_sdcard_pause() {
card.pausePrint();
print_job_counter.pause();
}
static void lcd_sdcard_resume() { card.startPrint(); }
static void lcd_sdcard_resume() {
card.startPrint();
print_job_counter.start();
}
static void lcd_sdcard_stop() {
quickStop();
card.sdprinting = false;
card.closeFile();
print_job_counter.stop();
autotempShutdown();
cancel_heatup = true;
lcd_setstatus(MSG_PRINT_ABORTED, true);
......@@ -577,26 +583,28 @@ inline void line_to_current(AxisEnum axis) {
*/
static void lcd_main_menu() {
START_MENU();
MENU_ITEM(back, MSG_WATCH);
#if ENABLED(LASER)
START_MENU();
MENU_ITEM(back, MSG_WATCH);
#if ENABLED(LASERBEAM)
if (!(movesplanned() || IS_SD_PRINTING)) {
MENU_ITEM(submenu, "Laser Functions", lcd_laser_menu);
}
#endif
if (movesplanned() || IS_SD_PRINTING) {
#endif
if (movesplanned() || IS_SD_PRINTING) {
MENU_ITEM(submenu, MSG_TUNE, lcd_tune_menu);
}
else {
}
else {
MENU_ITEM(submenu, MSG_PREPARE, lcd_prepare_menu);
#if MECH(DELTA)
MENU_ITEM(submenu, MSG_DELTA_CALIBRATE, lcd_delta_calibrate_menu);
#endif
}
MENU_ITEM(submenu, MSG_CONTROL, lcd_control_menu);
MENU_ITEM(submenu, MSG_STATS, lcd_stats_menu);
}
MENU_ITEM(submenu, MSG_CONTROL, lcd_control_menu);
MENU_ITEM(submenu, MSG_STATS, lcd_stats_menu);
#if ENABLED(SDSUPPORT)
#if ENABLED(SDSUPPORT)
if (card.cardOK) {
if (card.isFileOpen()) {
if (card.sdprinting)
......@@ -618,15 +626,15 @@ MENU_ITEM(submenu, MSG_STATS, lcd_stats_menu);
MENU_ITEM(gcode, MSG_INIT_SDCARD, PSTR("M21")); // Manually initialize the SD-card via user interface
#endif
}
#endif // SDSUPPORT
#endif // SDSUPPORT
END_MENU();
END_MENU();
}
#if ENABLED(SDSUPPORT) && ENABLED(MENU_ADDAUTOSTART)
static void lcd_autostart_sd() {
static void lcd_autostart_sd() {
card.checkautostart(true);
}
}
#endif
/**
......@@ -636,12 +644,12 @@ static void lcd_autostart_sd() {
*/
/**
* Set the home offset based on the current_position
*/
* Set the home offset based on the current_position
*/
void lcd_set_home_offsets() {
// M428 Command
enqueue_and_echo_commands_P(PSTR("M428"));
lcd_return_to_status();
// M428 Command
enqueue_and_echo_commands_P(PSTR("M428"));
lcd_return_to_status();
}
#if ENABLED(BABYSTEPPING)
......@@ -685,54 +693,54 @@ lcd_return_to_status();
if (LCD_CLICKED) lcd_goto_previous_menu(true);
}
#if ENABLED(BABYSTEP_XY)
#if ENABLED(BABYSTEP_XY)
static void _lcd_babystep_x() { _lcd_babystep(X_AXIS, PSTR(MSG_BABYSTEPPING_X)); }
static void _lcd_babystep_y() { _lcd_babystep(Y_AXIS, PSTR(MSG_BABYSTEPPING_Y)); }
static void lcd_babystep_x() { babysteps_done = 0; lcd_goto_menu(_lcd_babystep_x); }
static void lcd_babystep_y() { babysteps_done = 0; lcd_goto_menu(_lcd_babystep_y); }
#endif
static void _lcd_babystep_z() { _lcd_babystep(Z_AXIS, PSTR(MSG_BABYSTEPPING_Z)); }
static void lcd_babystep_z() { babysteps_done = 0; lcd_goto_menu(_lcd_babystep_z); }
#endif
static void _lcd_babystep_z() { _lcd_babystep(Z_AXIS, PSTR(MSG_BABYSTEPPING_Z)); }
static void lcd_babystep_z() { babysteps_done = 0; lcd_goto_menu(_lcd_babystep_z); }
#endif // BABYSTEPPING
static void lcd_tune_fixstep() {
#if MECH(DELTA)
#if MECH(DELTA)
enqueue_and_echo_commands_P(PSTR("G28 B"));
#else
#else
enqueue_and_echo_commands_P(PSTR("G28 X Y B"));
#endif
#endif
}
/**
* Watch temperature callbacks
*/
* Watch temperature callbacks
*/
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
#if TEMP_SENSOR_0 != 0
#if TEMP_SENSOR_0 != 0
void watch_temp_callback_E0() { start_watching_heater(0); }
#endif
#if HOTENDS > 1 && TEMP_SENSOR_1 != 0
#endif
#if HOTENDS > 1 && TEMP_SENSOR_1 != 0
void watch_temp_callback_E1() { start_watching_heater(1); }
#endif
#if HOTENDS > 2 && TEMP_SENSOR_2 != 0
#endif
#if HOTENDS > 2 && TEMP_SENSOR_2 != 0
void watch_temp_callback_E2() { start_watching_heater(2); }
#endif
#if HOTENDS > 3 && TEMP_SENSOR_3 != 0
#endif
#if HOTENDS > 3 && TEMP_SENSOR_3 != 0
void watch_temp_callback_E3() { start_watching_heater(3); }
#endif
#endif
#else
#if TEMP_SENSOR_0 != 0
#if TEMP_SENSOR_0 != 0
void watch_temp_callback_E0() {}
#endif
#if HOTENDS > 1 && TEMP_SENSOR_1 != 0
#endif
#if HOTENDS > 1 && TEMP_SENSOR_1 != 0
void watch_temp_callback_E1() {}
#endif
#if HOTENDS > 2 && TEMP_SENSOR_2 != 0
#endif
#if HOTENDS > 2 && TEMP_SENSOR_2 != 0
void watch_temp_callback_E2() {}
#endif
#if HOTENDS > 3 && TEMP_SENSOR_3 != 0
#endif
#if HOTENDS > 3 && TEMP_SENSOR_3 != 0
void watch_temp_callback_E3() {}
#endif
#endif
#endif // !THERMAL_PROTECTION_HOTENDS
#if ENABLED(THERMAL_PROTECTION_BED)
......@@ -746,29 +754,55 @@ static void lcd_tune_fixstep() {
#endif
/**
*
* "Tune" submenu
*
*/
*
* "Tune" submenu
*
*/
static void lcd_tune_menu() {
START_MENU();
//
// ^ Main
//
MENU_ITEM(back, MSG_MAIN);
//
// Speed:
//
MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_multiplier, 10, 999);
//
// Laser:
//
#if ENABLED(LASER) && ENABLED(COOLER)
START_MENU();
//
// ^ Main
//
MENU_ITEM(back, MSG_MAIN);
//
// Speed:
//
MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_multiplier, 10, 999);
//
// Nozzle:
//
#if HOTENDS == 1
#if TEMP_SENSOR_0 != 0
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15, watch_temp_callback_E0);
#endif
#else // HOTENDS > 1
#if TEMP_SENSOR_0 != 0
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE " 0", &target_temperature[0], 0, HEATER_0_MAXTEMP - 15, watch_temp_callback_E0);
#endif
#if TEMP_SENSOR_1 != 0
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE " 1", &target_temperature[1], 0, HEATER_1_MAXTEMP - 15, watch_temp_callback_E1);
#endif
#if HOTENDS > 2
#if TEMP_SENSOR_2 != 0
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE " 2", &target_temperature[2], 0, HEATER_2_MAXTEMP - 15, watch_temp_callback_E2);
#endif
#if HOTENDS > 3
#if TEMP_SENSOR_3 != 0
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_NOZZLE " 3", &target_temperature[3], 0, HEATER_3_MAXTEMP - 15, watch_temp_callback_E3);
#endif
#endif // HOTENDS > 3
#endif // HOTENDS > 2
#endif // HOTENDS > 1
//
// Laser:
//
#if ENABLED(LASERBEAM) && HAS(COOLER)
MENU_ITEM_EDIT(int3, MSG_COOLER, &target_temperature_cooler, 0, COOLER_MAXTEMP - 15);
#endif
#endif
//
// Bed:
......@@ -777,21 +811,21 @@ MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_multiplier, 10, 999);
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_BED, &target_temperature_bed, 0, BED_MAXTEMP - 15, watch_temp_callback_bed);
#endif
//
// Fan Speed:
//
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
//
// Fan Speed:
//
MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
//
// Flow:
// Flow 1:
// Flow 2:
// Flow 3:
// Flow 4:
//
#if EXTRUDERS == 1
//
// Flow:
// Flow 1:
// Flow 2:
// Flow 3:
// Flow 4:
//
#if EXTRUDERS == 1
MENU_ITEM_EDIT(int3, MSG_FLOW, &extruder_multiplier[0], 10, 999);
#else // EXTRUDERS > 1
#else // EXTRUDERS > 1
MENU_ITEM_EDIT(int3, MSG_FLOW, &extruder_multiplier[active_extruder], 10, 999);
MENU_ITEM_EDIT(int3, MSG_FLOW " 0", &extruder_multiplier[0], 10, 999);
MENU_ITEM_EDIT(int3, MSG_FLOW " 1", &extruder_multiplier[1], 10, 999);
......@@ -801,22 +835,22 @@ MENU_MULTIPLIER_ITEM_EDIT(int3, MSG_FAN_SPEED, &fanSpeed, 0, 255);
MENU_ITEM_EDIT(int3, MSG_FLOW " 3", &extruder_multiplier[3], 10, 999);
#endif // EXTRUDERS > 3
#endif // EXTRUDERS > 2
#endif // EXTRUDERS > 1
#endif // EXTRUDERS > 1
//
// Babystep X:
// Babystep Y:
// Babystep Z:
//
#if ENABLED(BABYSTEPPING)
//
// Babystep X:
// Babystep Y:
// Babystep Z:
//
#if ENABLED(BABYSTEPPING)
#if ENABLED(BABYSTEP_XY)
MENU_ITEM(submenu, MSG_BABYSTEP_X, lcd_babystep_x);
MENU_ITEM(submenu, MSG_BABYSTEP_Y, lcd_babystep_y);
#endif // BABYSTEP_XY
MENU_ITEM(submenu, MSG_BABYSTEP_Z, lcd_babystep_z);
#endif
#endif
MENU_ITEM(function, MSG_FIX_LOSE_STEPS, lcd_tune_fixstep);
MENU_ITEM(function, MSG_FIX_LOSE_STEPS, lcd_tune_fixstep);
//
// Change filament
......@@ -825,11 +859,11 @@ MENU_ITEM(function, MSG_FIX_LOSE_STEPS, lcd_tune_fixstep);
MENU_ITEM(gcode, MSG_FILAMENT_CHANGE, PSTR("M600"));
#endif
END_MENU();
END_MENU();
}
#if ENABLED(EASY_LOAD)
static void lcd_extrude(float length, float feedrate) {
static void lcd_extrude(float length, float feedrate) {
current_position[E_AXIS] += length;
#if MECH(DELTA)
calculate_delta(current_position);
......@@ -837,19 +871,19 @@ static void lcd_extrude(float length, float feedrate) {
#else
plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate, active_extruder, active_driver);
#endif
}
static void lcd_purge() { lcd_extrude(LCD_PURGE_LENGTH, LCD_PURGE_FEEDRATE); }
static void lcd_retract() { lcd_extrude(-LCD_RETRACT_LENGTH, LCD_RETRACT_FEEDRATE); }
static void lcd_easy_load() {
}
static void lcd_purge() { lcd_extrude(LCD_PURGE_LENGTH, LCD_PURGE_FEEDRATE); }
static void lcd_retract() { lcd_extrude(-LCD_RETRACT_LENGTH, LCD_RETRACT_FEEDRATE); }
static void lcd_easy_load() {
allow_lengthy_extrude_once = true;
lcd_extrude(BOWDEN_LENGTH, LCD_LOAD_FEEDRATE);
lcd_return_to_status();
}
static void lcd_easy_unload() {
}
static void lcd_easy_unload() {
allow_lengthy_extrude_once = true;
lcd_extrude(-BOWDEN_LENGTH, LCD_UNLOAD_FEEDRATE);
lcd_return_to_status();
}
}
#endif // EASY_LOAD
/**
......@@ -858,27 +892,27 @@ static void lcd_easy_unload() {
*
*/
void _lcd_preheat(int endnum, const float temph, const float tempb, const int fan) {
if (temph > 0) setTargetHotend(temph, endnum);
#if TEMP_SENSOR_BED != 0
if (temph > 0) setTargetHotend(temph, endnum);
#if TEMP_SENSOR_BED != 0
setTargetBed(tempb);
#else
#else
UNUSED(tempb);
#endif
fanSpeed = fan;
lcd_return_to_status();
#endif
fanSpeed = fan;
lcd_return_to_status();
}
#if TEMP_SENSOR_0 != 0
void lcd_preheat_pla0() { _lcd_preheat(0, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs0() { _lcd_preheat(0, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum0() { _lcd_preheat(0, gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed); }
void lcd_preheat_pla0() { _lcd_preheat(0, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs0() { _lcd_preheat(0, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum0() { _lcd_preheat(0, gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed); }
#endif
#if HOTENDS > 1
void lcd_preheat_pla1() { _lcd_preheat(1, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs1() { _lcd_preheat(1, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum1() { _lcd_preheat(1, gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed); }
#if HOTENDS > 2
void lcd_preheat_pla1() { _lcd_preheat(1, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs1() { _lcd_preheat(1, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum1() { _lcd_preheat(1, gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed); }
#if HOTENDS > 2
void lcd_preheat_pla2() { _lcd_preheat(2, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs2() { _lcd_preheat(2, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum2() { _lcd_preheat(2, gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed); }
......@@ -887,38 +921,38 @@ void lcd_preheat_gum1() { _lcd_preheat(1, gumPreheatHotendTemp, gumPreheatHPBTem
void lcd_preheat_abs3() { _lcd_preheat(3, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum3() { _lcd_preheat(3, gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed); }
#endif
#endif
#endif
void lcd_preheat_pla0123() {
void lcd_preheat_pla0123() {
setTargetHotend0(plaPreheatHotendTemp);
setTargetHotend1(plaPreheatHotendTemp);
setTargetHotend2(plaPreheatHotendTemp);
_lcd_preheat(3, plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed);
}
void lcd_preheat_abs0123() {
}
void lcd_preheat_abs0123() {
setTargetHotend0(absPreheatHotendTemp);
setTargetHotend1(absPreheatHotendTemp);
setTargetHotend2(absPreheatHotendTemp);
_lcd_preheat(3, absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed);
}
void lcd_preheat_gum0123() {
}
void lcd_preheat_gum0123() {
setTargetHotend0(gumPreheatHotendTemp);
setTargetHotend1(gumPreheatHotendTemp);
setTargetHotend2(gumPreheatHotendTemp);
_lcd_preheat(3, gumPreheatHotendTemp, gumPreheatHPBTemp, gumPreheatFanSpeed);
}
}
#endif // HOTENDS > 1
#if TEMP_SENSOR_BED != 0
void lcd_preheat_pla_bedonly() { _lcd_preheat(0, 0, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs_bedonly() { _lcd_preheat(0, 0, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum_bedonly() { _lcd_preheat(0, 0, gumPreheatHPBTemp, gumPreheatFanSpeed); }
void lcd_preheat_pla_bedonly() { _lcd_preheat(0, 0, plaPreheatHPBTemp, plaPreheatFanSpeed); }
void lcd_preheat_abs_bedonly() { _lcd_preheat(0, 0, absPreheatHPBTemp, absPreheatFanSpeed); }
void lcd_preheat_gum_bedonly() { _lcd_preheat(0, 0, gumPreheatHPBTemp, gumPreheatFanSpeed); }
#endif
#if TEMP_SENSOR_0 != 0 && (TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0)
static void lcd_preheat_pla_menu() {
static void lcd_preheat_pla_menu() {
START_MENU();
MENU_ITEM(back, MSG_PREPARE);
#if HOTENDS == 1
......@@ -938,9 +972,9 @@ static void lcd_preheat_pla_menu() {
MENU_ITEM(function, MSG_PREHEAT_PLA_BEDONLY, lcd_preheat_pla_bedonly);
#endif
END_MENU();
}
}
static void lcd_preheat_abs_menu() {
static void lcd_preheat_abs_menu() {
START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE);
#if HOTENDS == 1
......@@ -960,9 +994,9 @@ static void lcd_preheat_abs_menu() {
MENU_ITEM(function, MSG_PREHEAT_ABS_BEDONLY, lcd_preheat_abs_bedonly);
#endif
END_MENU();
}
}
static void lcd_preheat_gum_menu() {
static void lcd_preheat_gum_menu() {
START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE);
#if HOTENDS == 1
......@@ -982,22 +1016,22 @@ static void lcd_preheat_gum_menu() {
MENU_ITEM(function, MSG_PREHEAT_GUM_BEDONLY, lcd_preheat_gum_bedonly);
#endif
END_MENU();
}
}
#endif // TEMP_SENSOR_0 && (TEMP_SENSOR_1 || TEMP_SENSOR_2 || TEMP_SENSOR_3 || TEMP_SENSOR_BED)
void lcd_cooldown() {
disable_all_heaters();
disable_all_coolers();
fanSpeed = 0;
lcd_return_to_status();
disable_all_heaters();
disable_all_coolers();
fanSpeed = 0;
lcd_return_to_status();
}
/**
*
* "Prepare" submenu
*
*/
*
* "Prepare" submenu
*
*/
static void lcd_prepare_menu() {
START_MENU();
......@@ -1010,9 +1044,9 @@ static void lcd_prepare_menu() {
//
// Auto Home
//
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28 X Y F2000"));
# else
#else
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
#if !MECH(DELTA)
MENU_ITEM(gcode, MSG_AUTO_HOME_X, PSTR("G28 X"));
......@@ -1048,12 +1082,12 @@ static void lcd_prepare_menu() {
//
MENU_ITEM(gcode, MSG_DISABLE_STEPPERS, PSTR("M84"));
//
// Preheat PLA
// Preheat ABS
// Preheat GUM
//
#if TEMP_SENSOR_0 != 0 && DISABLED(LASER)
//
// Preheat PLA
// Preheat ABS
// Preheat GUM
//
#if TEMP_SENSOR_0 != 0 && DISABLED(LASERBEAM)
#if TEMP_SENSOR_1 != 0 || TEMP_SENSOR_2 != 0 || TEMP_SENSOR_3 != 0 || TEMP_SENSOR_BED != 0
MENU_ITEM(submenu, MSG_PREHEAT_PLA, lcd_preheat_pla_menu);
MENU_ITEM(submenu, MSG_PREHEAT_ABS, lcd_preheat_abs_menu);
......@@ -1063,59 +1097,46 @@ static void lcd_prepare_menu() {
MENU_ITEM(function, MSG_PREHEAT_ABS, lcd_preheat_abs0);
MENU_ITEM(function, MSG_PREHEAT_GUM, lcd_preheat_gum0);
#endif
#endif
#endif
//
// Easy Load
//
#if ENABLED(EASY_LOAD)
//
// Easy Load
//
#if ENABLED(EASY_LOAD)
MENU_ITEM(function, MSG_E_BOWDEN_LENGTH, lcd_easy_load);
MENU_ITEM(function, MSG_R_BOWDEN_LENGTH, lcd_easy_unload);
MENU_ITEM(function, MSG_PURGE_XMM, lcd_purge);
MENU_ITEM(function, MSG_RETRACT_XMM, lcd_retract);
#endif // EASY_LOAD
#endif // EASY_LOAD
//
// LASER BEAM
//
#if ENABLED(LASERBEAM)
MENU_ITEM_EDIT(int3, MSG_LASER, &laser_ttl_modulation, 0, 255);
if(laser_ttl_modulation == 0) {
WRITE(LASER_PWR_PIN, LOW);
}
else {
WRITE(LASER_PWR_PIN, HIGH);
}
#endif
//
// Cooldown
//
MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown);
//
// Cooldown
//
MENU_ITEM(function, MSG_COOLDOWN, lcd_cooldown);
//
// Switch power on/off
//
#if HAS(POWER_SWITCH)
//
// Switch power on/off
//
#if HAS(POWER_SWITCH)
if (powersupply)
MENU_ITEM(gcode, MSG_SWITCH_PS_OFF, PSTR("M81"));
else
MENU_ITEM(gcode, MSG_SWITCH_PS_ON, PSTR("M80"));
#endif
#endif
//
// Autostart
//
#if ENABLED(SDSUPPORT) && ENABLED(MENU_ADDAUTOSTART)
//
// Autostart
//
#if ENABLED(SDSUPPORT) && ENABLED(MENU_ADDAUTOSTART)
MENU_ITEM(function, MSG_AUTOSTART, lcd_autostart_sd);
#endif
#endif
END_MENU();
END_MENU();
}
#if MECH(DELTA)
static void lcd_delta_calibrate_menu() {
static void lcd_delta_calibrate_menu() {
START_MENU();
MENU_ITEM(back, MSG_MAIN);
MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28"));
......@@ -1124,21 +1145,21 @@ static void lcd_delta_calibrate_menu() {
MENU_ITEM(gcode, MSG_DELTA_CALIBRATE_Z, PSTR("G0 F8000 X0 Y90 Z0"));
MENU_ITEM(gcode, MSG_DELTA_CALIBRATE_CENTER, PSTR("G0 F8000 X0 Y0 Z0"));
END_MENU();
}
}
#endif // DELTA
/**
*
* "Prepare" > "Move Axis" submenu
*
*/
*
* "Prepare" > "Move Axis" submenu
*
*/
float move_menu_scale;
static void _lcd_move(const char* name, AxisEnum axis, int min, int max) {
ENCODER_DIRECTION_NORMAL();
if (encoderPosition != 0) {
ENCODER_DIRECTION_NORMAL();
if (encoderPosition != 0) {
refresh_cmd_timeout();
current_position[axis] += float((int)encoderPosition) * move_menu_scale;
if (SOFTWARE_MIN_ENDSTOPS) NOLESS(current_position[axis], min);
......@@ -1146,42 +1167,42 @@ if (encoderPosition != 0) {
encoderPosition = 0;
line_to_current(axis);
lcdDrawUpdate = LCDVIEW_REDRAW_NOW;
}
encoderPosition = 0;
if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr31(current_position[axis]));
if (LCD_CLICKED) lcd_goto_previous_menu(true);
}
encoderPosition = 0;
if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr31(current_position[axis]));
if (LCD_CLICKED) lcd_goto_previous_menu(true);
}
#if MECH(DELTA)
static float delta_clip_radius_2 = DELTA_PRINTABLE_RADIUS * DELTA_PRINTABLE_RADIUS;
static int delta_clip( float a ) { return sqrt(delta_clip_radius_2 - a * a); }
static void lcd_move_x() { int clip = delta_clip(current_position[Y_AXIS]); _lcd_move(PSTR(MSG_MOVE_X), X_AXIS, max(X_MIN_POS, -clip), min(X_MAX_POS, clip)); }
static void lcd_move_y() { int clip = delta_clip(current_position[X_AXIS]); _lcd_move(PSTR(MSG_MOVE_X), X_AXIS, max(X_MIN_POS, -clip), min(X_MAX_POS, clip)); }
static float delta_clip_radius_2 = DELTA_PRINTABLE_RADIUS * DELTA_PRINTABLE_RADIUS;
static int delta_clip( float a ) { return sqrt(delta_clip_radius_2 - a * a); }
static void lcd_move_x() { int clip = delta_clip(current_position[Y_AXIS]); _lcd_move(PSTR(MSG_MOVE_X), X_AXIS, max(X_MIN_POS, -clip), min(X_MAX_POS, clip)); }
static void lcd_move_y() { int clip = delta_clip(current_position[X_AXIS]); _lcd_move(PSTR(MSG_MOVE_X), X_AXIS, max(X_MIN_POS, -clip), min(X_MAX_POS, clip)); }
#else
static void lcd_move_x() { _lcd_move(PSTR(MSG_MOVE_X), X_AXIS, X_MIN_POS, X_MAX_POS); }
static void lcd_move_y() { _lcd_move(PSTR(MSG_MOVE_Y), Y_AXIS, Y_MIN_POS, Y_MAX_POS); }
static void lcd_move_x() { _lcd_move(PSTR(MSG_MOVE_X), X_AXIS, X_MIN_POS, X_MAX_POS); }
static void lcd_move_y() { _lcd_move(PSTR(MSG_MOVE_Y), Y_AXIS, Y_MIN_POS, Y_MAX_POS); }
#endif
static void lcd_move_z() { _lcd_move(PSTR(MSG_MOVE_Z), Z_AXIS, Z_MIN_POS, Z_MAX_POS); }
static void lcd_move_e(
#if EXTRUDERS > 1
#if EXTRUDERS > 1
uint8_t e
#endif
#endif
) {
ENCODER_DIRECTION_NORMAL();
#if EXTRUDERS > 1
ENCODER_DIRECTION_NORMAL();
#if EXTRUDERS > 1
unsigned short original_active_extruder = active_extruder;
active_extruder = e;
#endif
if (encoderPosition != 0) {
#endif
if (encoderPosition != 0) {
#if ENABLED(IDLE_OOZING_PREVENT)
IDLE_OOZING_retract(false);
#endif
current_position[E_AXIS] += float((int)encoderPosition) * move_menu_scale;
line_to_current(E_AXIS);
lcdDrawUpdate = LCDVIEW_REDRAW_NOW;
}
encoderPosition = 0;
if (lcdDrawUpdate) {
}
encoderPosition = 0;
if (lcdDrawUpdate) {
PGM_P pos_label;
#if EXTRUDERS == 1
pos_label = PSTR(MSG_MOVE_E);
......@@ -1198,46 +1219,46 @@ if (lcdDrawUpdate) {
}
#endif // EXTRUDERS > 1
lcd_implementation_drawedit(pos_label, ftostr31(current_position[E_AXIS]));
}
if (LCD_CLICKED) lcd_goto_previous_menu(true);
#if EXTRUDERS > 1
}
if (LCD_CLICKED) lcd_goto_previous_menu(true);
#if EXTRUDERS > 1
active_extruder = original_active_extruder;
#endif
#endif
}
#if EXTRUDERS > 1
static void lcd_move_e0() { lcd_move_e(0); }
static void lcd_move_e1() { lcd_move_e(1); }
#if EXTRUDERS > 2
static void lcd_move_e0() { lcd_move_e(0); }
static void lcd_move_e1() { lcd_move_e(1); }
#if EXTRUDERS > 2
static void lcd_move_e2() { lcd_move_e(2); }
#if EXTRUDERS > 3
static void lcd_move_e3() { lcd_move_e(3); }
#endif // EXTRUDERS > 3
#endif // EXTRUDERS > 2
#endif // EXTRUDERS > 2
#endif // EXTRUDERS > 1
/**
*
* "Prepare" > "Move Xmm" > "Move XYZ" submenu
*
*/
*
* "Prepare" > "Move Xmm" > "Move XYZ" submenu
*
*/
#if MECH(DELTA) || MECH(SCARA)
#define _MOVE_XYZ_ALLOWED (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS])
#define _MOVE_XYZ_ALLOWED (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS])
#else
#define _MOVE_XYZ_ALLOWED true
#define _MOVE_XYZ_ALLOWED true
#endif
static void lcd_move_menu_axis() {
START_MENU();
MENU_ITEM(back, MSG_MOVE_AXIS);
START_MENU();
MENU_ITEM(back, MSG_MOVE_AXIS);
if (_MOVE_XYZ_ALLOWED) {
if (_MOVE_XYZ_ALLOWED) {
MENU_ITEM(submenu, MSG_MOVE_X, lcd_move_x);
MENU_ITEM(submenu, MSG_MOVE_Y, lcd_move_y);
MENU_ITEM(submenu, MSG_MOVE_Z, lcd_move_z);
}
if (move_menu_scale < 10.0) {
}
if (move_menu_scale < 10.0) {
#if EXTRUDERS == 1
MENU_ITEM(submenu, MSG_MOVE_E, lcd_move_e);
#else
......@@ -1250,56 +1271,56 @@ if (move_menu_scale < 10.0) {
#endif // EXTRUDERS > 3
#endif // EXTRUDERS > 2
#endif // EXTRUDERS > 1
}
END_MENU();
}
END_MENU();
}
static void lcd_move_menu_10mm() {
move_menu_scale = 10.0;
lcd_move_menu_axis();
move_menu_scale = 10.0;
lcd_move_menu_axis();
}
static void lcd_move_menu_1mm() {
move_menu_scale = 1.0;
lcd_move_menu_axis();
move_menu_scale = 1.0;
lcd_move_menu_axis();
}
static void lcd_move_menu_01mm() {
move_menu_scale = 0.1;
lcd_move_menu_axis();
move_menu_scale = 0.1;
lcd_move_menu_axis();
}
/**
*
* "Prepare" > "Move Axis" submenu
*
*/
*
* "Prepare" > "Move Axis" submenu
*
*/
static void lcd_move_menu() {
START_MENU();
MENU_ITEM(back, MSG_PREPARE);
START_MENU();
MENU_ITEM(back, MSG_PREPARE);
if (_MOVE_XYZ_ALLOWED)
if (_MOVE_XYZ_ALLOWED)
MENU_ITEM(submenu, MSG_MOVE_10MM, lcd_move_menu_10mm);
MENU_ITEM(submenu, MSG_MOVE_1MM, lcd_move_menu_1mm);
MENU_ITEM(submenu, MSG_MOVE_01MM, lcd_move_menu_01mm);
// TODO:X,Y,Z,E
END_MENU();
MENU_ITEM(submenu, MSG_MOVE_1MM, lcd_move_menu_1mm);
MENU_ITEM(submenu, MSG_MOVE_01MM, lcd_move_menu_01mm);
// TODO:X,Y,Z,E
END_MENU();
}
/**
*
* "Control" submenu
*
*/
*
* "Control" submenu
*
*/
static void lcd_control_menu() {
START_MENU();
MENU_ITEM(back, MSG_MAIN);
#if DISABLED(LASER)
#if DISABLED(LASERBEAM)
MENU_ITEM(submenu, MSG_TEMPERATURE, lcd_control_temperature_menu);
#endif
MENU_ITEM(submenu, MSG_MOTION, lcd_control_motion_menu);
#if DISABLED(LASER)
#if DISABLED(LASERBEAM)
MENU_ITEM(submenu, MSG_FILAMENT, lcd_control_volumetric_menu);
#endif
......@@ -1352,7 +1373,7 @@ static void lcd_stats_menu() {
#if ENABLED(PID_AUTOTUNE_MENU)
#if ENABLED(PIDTEMP)
int autotune_temp[HOTENDS] = { 150 };
int autotune_temp[HOTENDS] = ARRAY_BY_HOTENDS1(150);
const int heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP);
#endif
......@@ -1413,13 +1434,14 @@ static void lcd_stats_menu() {
#endif // PIDTEMP
/**
#if DISABLED(LASERBEAM)
/**
*
* "Control" > "Temperature" submenu
*
*/
#if DISABLED(LASER)
static void lcd_control_temperature_menu() {
static void lcd_control_temperature_menu() {
START_MENU();
//
......@@ -1525,7 +1547,6 @@ static void lcd_control_temperature_menu() {
MENU_ITEM_EDIT(bool, MSG_IDLEOOZING, &IDLE_OOZING_enabled);
#endif
#if DISABLED(LASER)
//
// Preheat PLA conf
//
......@@ -1540,19 +1561,15 @@ static void lcd_control_temperature_menu() {
// Preheat GUM conf
//
MENU_ITEM(submenu, MSG_PREHEAT_GUM_SETTINGS, lcd_control_temperature_preheat_gum_settings_menu);
#endif
END_MENU();
}
#endif
}
/**
/**
*
* "Temperature" > "Preheat PLA conf" submenu
*
*/
#if DISABLED(LASER)
static void lcd_control_temperature_preheat_pla_settings_menu() {
static void lcd_control_temperature_preheat_pla_settings_menu() {
START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &plaPreheatFanSpeed, 0, 255);
......@@ -1566,16 +1583,14 @@ static void lcd_control_temperature_preheat_pla_settings_menu() {
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
#endif
END_MENU();
}
#endif
}
/**
/**
*
* "Temperature" > "Preheat ABS conf" submenu
*
*/
#if DISABLED(LASER)
static void lcd_control_temperature_preheat_abs_settings_menu() {
static void lcd_control_temperature_preheat_abs_settings_menu() {
START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &absPreheatFanSpeed, 0, 255);
......@@ -1589,15 +1604,14 @@ static void lcd_control_temperature_preheat_abs_settings_menu() {
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
#endif
END_MENU();
}
#endif
/**
}
/**
*
* "Temperature" > "Preheat GUM conf" submenu
*
*/
#if DISABLED(LASER)
static void lcd_control_temperature_preheat_gum_settings_menu() {
static void lcd_control_temperature_preheat_gum_settings_menu() {
START_MENU();
MENU_ITEM(back, MSG_TEMPERATURE);
MENU_ITEM_EDIT(int3, MSG_FAN_SPEED, &gumPreheatFanSpeed, 0, 255);
......@@ -1611,8 +1625,10 @@ static void lcd_control_temperature_preheat_gum_settings_menu() {
MENU_ITEM(function, MSG_STORE_EPROM, Config_StoreSettings);
#endif
END_MENU();
}
#endif
}
#endif // !LASERBEAM
/**
*
* "Control" > "Motion" submenu
......@@ -1683,8 +1699,8 @@ static void lcd_control_motion_menu() {
* "Control" > "Filament" submenu
*
*/
#if DISABLED(LASER)
static void lcd_control_volumetric_menu() {
#if DISABLED(LASERBEAM)
static void lcd_control_volumetric_menu() {
START_MENU();
MENU_ITEM(back, MSG_CONTROL);
......@@ -1706,8 +1722,8 @@ static void lcd_control_volumetric_menu() {
}
END_MENU();
}
#endif
}
#endif // !LASERBEAM
/**
*
......@@ -1765,24 +1781,25 @@ static void lcd_control_volumetric_menu() {
}
#endif // FWRETRACT
#if ENABLED(LASER)
static void lcd_laser_menu()
{
#if ENABLED(LASERBEAM)
static void lcd_laser_menu() {
START_MENU();
MENU_ITEM(back, MSG_MAIN);
MENU_ITEM(submenu, "Set Focus", lcd_laser_focus_menu);
MENU_ITEM(submenu, "Test Fire", lcd_laser_test_fire_menu);
#ifdef LASER_PERIPHERALS
#if ENABLED(LASER_PERIPHERALS)
if (laser_peripherals_ok()) {
MENU_ITEM(function, "Turn On Pumps/Fans", action_laser_acc_on);
} else if (!(movesplanned() || IS_SD_PRINTING)) {
}
else if (!(movesplanned() || IS_SD_PRINTING)) {
MENU_ITEM(function, "Turn Off Pumps/Fans", action_laser_acc_off);
}
#endif // LASER_PERIPHERALS
END_MENU();
}
}
static void lcd_laser_test_fire_menu() {
static void lcd_laser_test_fire_menu() {
START_MENU();
MENU_ITEM(back, "Laser Functions");
MENU_ITEM(function, " 20% 50ms", action_laser_test_20_50ms);
......@@ -1791,44 +1808,25 @@ static void lcd_laser_test_fire_menu() {
MENU_ITEM(function, "100% 100ms", action_laser_test_100_100ms);
MENU_ITEM(function, "Warm-up Laser 2sec", action_laser_test_warm);
END_MENU();
}
static void action_laser_acc_on() {
enqueue_and_echo_commands_P(PSTR("M80"));
}
static void action_laser_acc_off() {
enqueue_and_echo_commands_P(PSTR("M81"));
}
static void action_laser_test_20_50ms() {
laser_test_fire(20, 50);
}
static void action_laser_test_20_100ms() {
laser_test_fire(20, 100);
}
static void action_laser_test_100_50ms() {
laser_test_fire(100, 50);
}
static void action_laser_test_100_100ms() {
laser_test_fire(100, 100);
}
}
static void action_laser_test_warm() {
laser_test_fire(15, 2000);
}
static void action_laser_acc_on() { enqueue_and_echo_commands_P(PSTR("M80")); }
static void action_laser_acc_off() { enqueue_and_echo_commands_P(PSTR("M81")); }
static void action_laser_test_20_50ms() { laser_test_fire(20, 50); }
static void action_laser_test_20_100ms() { laser_test_fire(20, 100); }
static void action_laser_test_100_50ms() { laser_test_fire(100, 50); }
static void action_laser_test_100_100ms() { laser_test_fire(100, 100); }
static void action_laser_test_warm() { laser_test_fire(15, 2000); }
static void laser_test_fire(uint8_t power, int dwell) {
static void laser_test_fire(uint8_t power, int dwell) {
enqueue_and_echo_commands_P(PSTR("M80")); // Enable laser accessories since we don't know if its been done (and there's no penalty for doing it again).
laser_fire(power);
delay(dwell);
laser_extinguish();
}
float focalLength = 0;
static void lcd_laser_focus_menu() {
}
float focalLength = 0;
static void lcd_laser_focus_menu() {
START_MENU();
MENU_ITEM(back, "Laser Functions");
MENU_ITEM(function, "1mm", action_laser_focus_1mm);
......@@ -1840,39 +1838,18 @@ static void lcd_laser_focus_menu() {
MENU_ITEM(function, "7mm", action_laser_focus_7mm);
MENU_ITEM_EDIT_CALLBACK(float32, "Custom", &focalLength, 0, LASER_FOCAL_HEIGHT, action_laser_focus_custom);
END_MENU();
}
static void action_laser_focus_custom() {
laser_set_focus(focalLength);
}
static void action_laser_focus_1mm() {
laser_set_focus(1);
}
static void action_laser_focus_2mm() {
laser_set_focus(2);
}
static void action_laser_focus_3mm() {
laser_set_focus(3);
}
}
static void action_laser_focus_4mm() {
laser_set_focus(4);
}
static void action_laser_focus_custom() { laser_set_focus(focalLength); }
static void action_laser_focus_1mm() { laser_set_focus(1); }
static void action_laser_focus_2mm() { laser_set_focus(2); }
static void action_laser_focus_3mm() { laser_set_focus(3); }
static void action_laser_focus_4mm() { laser_set_focus(4); }
static void action_laser_focus_5mm() { laser_set_focus(5); }
static void action_laser_focus_6mm() { laser_set_focus(6); }
static void action_laser_focus_7mm() { laser_set_focus(7); }
static void action_laser_focus_5mm() {
laser_set_focus(5);
}
static void action_laser_focus_6mm() {
laser_set_focus(6);
}
static void action_laser_focus_7mm() {
laser_set_focus(7);
}
static void laser_set_focus(float f_length) {
static void laser_set_focus(float f_length) {
if (!axis_homed[Z_AXIS]) {
enqueue_and_echo_commands_P(PSTR("G28 Z F150"));
}
......@@ -1882,9 +1859,9 @@ static void laser_set_focus(float f_length) {
sprintf_P(cmd, PSTR("G0 Z%s F150"), ftostr52(focus));
enqueue_and_echo_commands_P(cmd);
}
}
#endif // LASER
#endif // LASERBEAM
#if ENABLED(SDSUPPORT)
......
......@@ -21,61 +21,61 @@
*/
#ifndef MACROS_H
#define MACROS_H
#define MACROS_H
// Compiler warning on unused varable.
#define UNUSED(x) (void) (x)
// Compiler warning on unused varable.
#define UNUSED(x) (void) (x)
// Macros for bit masks
#ifndef _BV
// Macros for bit masks
#ifndef _BV
#define _BV(b) (1<<(b))
#endif
#define TEST(n,b) (((n)&_BV(b))!=0)
#define SBI(n,b) (n |= _BV(b))
#define CBI(n,b) (n &= ~_BV(b))
#define SET_BIT(n,b,value) (n) ^= ((-value)^(n)) & (_BV(b))
#endif
#define TEST(n,b) (((n)&_BV(b))!=0)
#define SBI(n,b) (n |= _BV(b))
#define CBI(n,b) (n &= ~_BV(b))
#define SET_BIT(n,b,value) (n) ^= ((-value)^(n)) & (_BV(b))
// Macros for maths shortcuts
#ifndef M_PI
// Macros for maths shortcuts
#ifndef M_PI
#define M_PI 3.1415926536
#endif
#define RADIANS(d) ((d)*M_PI/180.0)
#define DEGREES(r) ((r)*180.0/M_PI)
#define SIN_60 0.8660254037844386
#define COS_60 0.5
#endif
#define RADIANS(d) ((d)*M_PI/180.0)
#define DEGREES(r) ((r)*180.0/M_PI)
#define SIN_60 0.8660254037844386
#define COS_60 0.5
// Macros to support option testing
#define ENABLED defined
#define DISABLED !defined
// Macros to support option testing
#define ENABLED defined
#define DISABLED !defined
#define HAS(FE) (HAS_##FE)
#define HASNT(FE) (!(HAS_##FE))
#define HAS(FE) (HAS_##FE)
#define HASNT(FE) (!(HAS_##FE))
// Macros to contrain values
#define NUMERIC(a) ((a) >= '0' && '9' >= (a))
#define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-')
#define NOLESS(v,n) do{ if (v < n) v = n; }while(0)
#define NOMORE(v,n) do{ if (v > n) v = n; }while(0)
#define COUNT(a) (sizeof(a)/sizeof(*a))
// Macros to contrain values
#define NUMERIC(a) ((a) >= '0' && '9' >= (a))
#define NUMERIC_SIGNED(a) (NUMERIC(a) || (a) == '-')
#define NOLESS(v,n) do{ if (v < n) v = n; }while(0)
#define NOMORE(v,n) do{ if (v > n) v = n; }while(0)
#define COUNT(a) (sizeof(a)/sizeof(*a))
// Function macro
#define FORCE_INLINE __attribute__((always_inline)) inline
// Function macro
#define FORCE_INLINE __attribute__((always_inline)) inline
// Macro for debugging
#define DEBUGGING(F) (mk_debug_flags & (DEBUG_## F))
// Macro for debugging
#define DEBUGGING(F) (mk_debug_flags & (DEBUG_## F))
// Macro for String
#define STRINGIFY_(n) #n
#define STRINGIFY(n) STRINGIFY_(n)
// Macro for String
#define STRINGIFY_(n) #n
#define STRINGIFY(n) STRINGIFY_(n)
// Macro for varie
#define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0)
// Macro for varie
#define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0)
#define PENDING(NOW,SOON) ((long)(NOW-(SOON))<0)
#define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON))
#define PENDING(NOW,SOON) ((long)(NOW-(SOON))<0)
#define ELAPSED(NOW,SOON) (!PENDING(NOW,SOON))
#define NOOP do{}while(0)
#define NOOP do{}while(0)
#define _AXIS(AXIS) AXIS ##_AXIS
#define _AXIS(AXIS) AXIS ##_AXIS
#endif //__MACROS_H
......@@ -21,18 +21,18 @@
*/
#ifndef MECHANICS_H
#define MECHANICS_H
#define MECHANICS_H
// Macros for mechanics type
#define MECH_UNKNOWN -1
#define MECH_CARTESIAN 0
#define MECH_COREXY 1
#define MECH_COREYX 2
#define MECH_COREXZ 8
#define MECH_COREZX 9
#define MECH_DELTA 3
#define MECH_SCARA 4
// Macros for mechanics type
#define MECH_UNKNOWN -1
#define MECH_CARTESIAN 0
#define MECH_COREXY 1
#define MECH_COREYX 2
#define MECH_COREXZ 8
#define MECH_COREZX 9
#define MECH_DELTA 3
#define MECH_SCARA 4
#define MECH(mech) (MECHANISM == MECH_##mech)
#define MECH(mech) (MECHANISM == MECH_##mech)
#endif
\ No newline at end of file
......@@ -417,9 +417,7 @@ void check_axes_activity() {
unsigned char tail_valve_pressure = ValvePressure,
tail_e_to_p_pressure = EtoPPressure;
#endif
#if ENABLED(LASERBEAM)
unsigned char tail_laser_ttl_modulation = laser_ttl_modulation;
#endif
block_t* block;
if (blocks_queued()) {
......@@ -430,9 +428,6 @@ void check_axes_activity() {
tail_valve_pressure = block->valve_pressure;
tail_e_to_p_pressure = block->e_to_p_pressure;
#endif
#if ENABLED(LASERBEAM)
tail_laser_ttl_modulation = block_buffer[block_index].laser_ttlmodulation;
#endif
while (block_index != block_buffer_head) {
block = &block_buffer[block_index];
......@@ -493,10 +488,6 @@ void check_axes_activity() {
#endif
#endif
// add Laser TTL Modulation(PWM) Control
#if ENABLED(LASERBEAM)
analogWrite(LASER_TTL_PIN, tail_laser_ttl_modulation);
#endif
}
float junction_deviation = 0.1;
......@@ -629,7 +620,7 @@ float junction_deviation = 0.1;
block->steps[E_AXIS] /= 100;
block->step_event_count = max(block->steps[X_AXIS], max(block->steps[Y_AXIS], max(block->steps[Z_AXIS], block->steps[E_AXIS])));
#if DISABLED(LASER)
#if DISABLED(LASERBEAM)
// Bail if this is a zero-length block
if (block->step_event_count <= DROP_SEGMENTS) return;
#endif
......@@ -647,11 +638,6 @@ float junction_deviation = 0.1;
block->mix_event_count[i] = block->steps[E_AXIS] * mixing_factor[i];
#endif
// Add update block variables for LASER BEAM control
#if ENABLED(LASERBEAM)
block->laser_ttlmodulation = laser_ttl_modulation;
#endif
// Compute direction bits for this block
uint8_t dirb = 0;
#if MECH(COREXY) || MECH(COREYX)
......@@ -882,7 +868,7 @@ float junction_deviation = 0.1;
);
}
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
block->laser_intensity = laser.intensity;
block->laser_duration = laser.duration;
block->laser_status = laser.status;
......@@ -915,19 +901,16 @@ float junction_deviation = 0.1;
#endif
}
}
} else {
block->steps_l = 0;
}
else
block->steps_l = 0;
block->step_event_count = max(block->steps[X_AXIS], max(block->steps[Y_AXIS], max(block->steps[Z_AXIS], max(block->steps[E_AXIS], block->steps_l))));
if (laser.diagnostics) {
if (block->laser_status == LASER_ON) {
if (laser.diagnostics && block->laser_status == LASER_ON)
ECHO_LM(INFO, "Laser firing enabled");
}
}
#endif // LASER
#endif // LASERBEAM
float inverse_millimeters = 1.0 / block->millimeters; // Inverse millimeters to remove multiple divides
......
......@@ -99,7 +99,7 @@ typedef struct {
unsigned long e_to_p_pressure;
#endif
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
uint8_t laser_mode; // CONTINUOUS, PULSED, RASTER
bool laser_status; // LASER_OFF, LASER_ON
float laser_ppm; // pulses per millimeter, for pulsed and raster firing modes
......@@ -112,10 +112,6 @@ typedef struct {
#endif
#endif
#if ENABLED(LASERBEAM)
unsigned long laser_ttlmodulation;
#endif
volatile char busy;
} block_t;
......
......@@ -68,15 +68,12 @@ block_t* current_block; // A pointer to the block currently being traced
static unsigned char last_direction_bits = 0; // The next stepping-bits to be output
static unsigned int cleaning_buffer_counter = 0;
#ifdef LASER
static long counter_L;
#endif // LASER
#ifdef LASER_RASTER
static int counter_raster;
#endif // LASER_RASTER
#if ENABLED(LASERBEAM)
static long counter_L;
#if ENABLED(LASER_RASTER)
static int counter_raster;
#endif // LASER_RASTER
#endif // LASERBEAM
#if ENABLED(Z_DUAL_ENDSTOPS)
static bool performing_homing = false,
......@@ -124,7 +121,7 @@ static unsigned short OCR1A_nominal;
static bool check_endstops = true;
volatile long count_position[NUM_AXIS] = { 0 }; // Positions of stepper motors, in step units
volatile signed char count_direction[NUM_AXIS] = { 1 };
volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1 };
//===========================================================================
......@@ -307,11 +304,11 @@ FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) {
NOMORE(step_rate, MAX_STEP_FREQUENCY);
if(step_rate > (2 * DOUBLE_STEP_FREQUENCY)) { // If steprate > 2*DOUBLE_STEP_FREQUENCY >> step 4 times
step_rate = (step_rate >> 2);
step_rate >>= 2;
step_loops = 4;
}
else if(step_rate > DOUBLE_STEP_FREQUENCY) { // If steprate > DOUBLE_STEP_FREQUENCY >> step 2 times
step_rate = (step_rate >> 1);
step_rate >>= 1;
step_loops = 2;
}
else {
......@@ -429,9 +426,11 @@ ISR(TIMER1_COMPA_vect) {
return;
}
#if ENABLED(LASER) && (!ENABLED(LASER_PULSE_METHOD))
#if ENABLED(LASERBEAM) && (!ENABLED(LASER_PULSE_METHOD))
if (laser.dur != 0 && (laser.last_firing + laser.dur < micros())) {
if (laser.diagnostics) ECHO_LM(INFO,"Laser firing duration elapsed, in interrupt handler");
if (laser.diagnostics)
ECHO_LM(INFO, "Laser firing duration elapsed, in interrupt handler");
laser_extinguish();
}
#endif
......@@ -446,7 +445,8 @@ ISR(TIMER1_COMPA_vect) {
// Initialize Bresenham counters to 1/2 the ceiling
counter_X = counter_Y = counter_Z = counter_E = -(current_block->step_event_count >> 1);
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
counter_L = counter_X;
#if !ENABLED(LASER_PULSE_METHOD)
laser.dur = current_block->laser_duration;
......@@ -463,15 +463,12 @@ ISR(TIMER1_COMPA_vect) {
#if ENABLED(Z_LATE_ENABLE)
if (current_block->steps[Z_AXIS] > 0) {
enable_z();
#if ENABLED(MUVE)
enable_e();
#endif
OCR1A = 2000; // 1ms wait
return;
}
#endif
#if ENABLED(LASER_RASTER)
#if ENABLED(LASERBEAM) && ENABLED(LASER_RASTER)
if (current_block->laser_mode == RASTER) counter_raster = 0;
#endif
......@@ -494,10 +491,10 @@ ISR(TIMER1_COMPA_vect) {
#endif
// Continuous firing of the laser during a move happens here, PPM and raster happen further down
#if ENABLED(LASER)
if (current_block->laser_mode == CONTINUOUS && current_block->laser_status == LASER_ON) {
#if ENABLED(LASERBEAM)
if (current_block->laser_mode == CONTINUOUS && current_block->laser_status == LASER_ON)
laser_fire(current_block->laser_intensity);
}
#if !ENABLED(LASER_PULSE_METHOD)
if (current_block->laser_status == LASER_OFF) {
if (laser.diagnostics) ECHO_LM(INFO,"Laser status set to off, in interrupt handler");
......@@ -600,14 +597,14 @@ ISR(TIMER1_COMPA_vect) {
#endif
#endif
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
counter_L += current_block->steps_l;
if (counter_L > 0) {
if (current_block->laser_mode == PULSED && current_block->laser_status == LASER_ON) { // Pulsed Firing Mode
#if ENABLED(LASER_PULSE_METHOD)
uint32_t ulValue = current_block->laser_raster_intensity_factor * 255;
laser_pulse(ulValue, current_block->laser_duration);
laser.time += current_block->laser_duration/1000;
laser.time += current_block->laser_duration / 1000;
#else
laser_fire(current_block->laser_intensity);
#endif
......@@ -652,7 +649,7 @@ ISR(TIMER1_COMPA_vect) {
laser_extinguish();
}
#endif
#endif // LASER
#endif // LASERBEAM
// safe check for erroneous calculated events count
if(current_block->step_event_count >= MAX_EVENTS_COUNT) {
......@@ -767,10 +764,9 @@ ISR(TIMER1_COMPA_vect) {
if (step_events_completed >= current_block->step_event_count) {
current_block = NULL;
plan_discard_current_block();
#if ENABLED(LASER) && ENABLED(LASER_PULSE_METHOD)
if (current_block->laser_mode == CONTINUOUS && current_block->laser_status == LASER_ON) {
#if ENABLED(LASERBEAM) && ENABLED(LASER_PULSE_METHOD)
if (current_block->laser_mode == CONTINUOUS && current_block->laser_status == LASER_ON)
laser_extinguish();
}
#endif
}
}
......
......@@ -352,12 +352,12 @@
#define COOLER_PIN -1
#endif
#ifndef LASER_FIRING_PIN
#define LASER_FIRING_PIN -1
#ifndef LASER_PWR_PIN
#define LASER_PWR_PIN -1
#endif
#ifndef LASER_INTENSITY_PIN
#define LASER_INTENSITY_PIN -1
#ifndef LASER_TTL_PIN
#define LASER_TTL_PIN -1
#endif
#ifndef FLOWMETER_PIN
......@@ -373,7 +373,7 @@
_E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS \
analogInputToDigitalPin(TEMP_BED_PIN), \
analogInputToDigitalPin(TEMP_COOLER_PIN), \
COOLER_PIN, LASER_FIRING_PIN, LASER_INTENSITY_PIN, \
COOLER_PIN, LASER_PWR_PIN, LASER_TTL_PIN, \
FLOWMETER_PIN \
}
......
......@@ -165,6 +165,7 @@ bool PrintCounter::stop() {
this->data.completePrints++;
this->data.printTime += this->deltaDuration();
this->saveStats();
return true;
}
else return false;
}
......
......@@ -82,15 +82,18 @@
#if DISABLED(TEMP_SENSOR_BED)
#error DEPENDENCY ERROR: Missing setting TEMP_SENSOR_BED
#endif
#if DISABLED(TEMP_SENSOR_CHAMBER)
#error DEPENDENCY_ERROR: Missing setting TEMP_SENSOR_CHAMBER
#endif
#if DISABLED(TEMP_SENSOR_COOLER)
#error DEPENDENCY_ERROR: Missing setting TEMP_SENSOR_COOLER
#endif
#if (THERMISTORHEATER_0 == 998) || (THERMISTORHEATER_1 == 998) || (THERMISTORHEATER_2 == 998) || (THERMISTORHEATER_3 == 998) || (THERMISTORBED == 998) || (THERMISTORCOOLER == 998) //User EXIST table
#if (THERMISTORHEATER_0 == 998) || (THERMISTORHEATER_1 == 998) || (THERMISTORHEATER_2 == 998) || (THERMISTORHEATER_3 == 998) || (THERMISTORBED == 998) || (THERMISTORCHAMBER == 998) || (THERMISTORCOOLER == 998) // User EXIST table
#if DISABLED(DUMMY_THERMISTOR_998_VALUE)
#define DUMMY_THERMISTOR_998_VALUE 25
#endif
#endif
#if (THERMISTORHEATER_0 == 999) || (THERMISTORHEATER_1 == 999) || (THERMISTORHEATER_2 == 999) || (THERMISTORHEATER_3 == 999) || (THERMISTORBED == 999) || (THERMISTORCOOLER == 999)//User EXIST table
#if (THERMISTORHEATER_0 == 999) || (THERMISTORHEATER_1 == 999) || (THERMISTORHEATER_2 == 999) || (THERMISTORHEATER_3 == 999) || (THERMISTORBED == 999) || (THERMISTORCHAMBER == 999) || (THERMISTORCOOLER == 999)// User EXIST table
#if DISABLED(DUMMY_THERMISTOR_999_VALUE)
#define DUMMY_THERMISTOR_999_VALUE 25
#endif
......@@ -148,6 +151,17 @@
#error DEPENDENCY ERROR: Missing setting BED_MINTEMP
#endif
#endif
#if TEMP_SENSOR_CHAMBER != 0
#if DISABLED(CHAMBER_MAXTEMP)
#error DEPENDENCY ERROR: Missing setting CHAMBER_MAXTEMP
#endif
#if DISABLED(CHAMBER_MINTEMP)
#error DEPENDENCY ERROR: Missing setting CHAMBER_MINTEMP
#endif
#if HASNT(HEATER_CHAMBER)
#error DEPENDENCY ERROR: Cannot enable TEMP_SENSOR_CHAMBER and not HEATER_CHAMBER_PIN
#endif
#endif
#if TEMP_SENSOR_COOLER != 0
#if DISABLED(COOLER_MAXTEMP)
#error DEPENDENCY ERROR: Missing setting COOLER_MAXTEMP
......@@ -155,8 +169,8 @@
#if DISABLED(COOLER_MINTEMP)
#error DEPENDENCY ERROR: Missing setting COOLER_MINTEMP
#endif
#if DISABLED(COOLER)
#error DEPENDENCY ERROR: Cannot enable TEMP_SENSOR_COOLER and not COOLER
#if HASNT(COOLER)
#error DEPENDENCY ERROR: Cannot enable TEMP_SENSOR_COOLER and not COOLER_PIN
#endif
#endif
#if DISABLED(PLA_PREHEAT_HOTEND_TEMP)
......@@ -201,10 +215,13 @@
#if DISABLED(MAX_BED_POWER)
#error DEPENDENCY ERROR: Missing setting MAX_BED_POWER
#endif
#if DISABLED(MAX_CHAMBER_POWER)
#error DEPENDENCY ERROR: Missing setting MAX_CHAMBER_POWER
#endif
#if DISABLED(MAX_COOLER_POWER)
#error DEPENDENCY ERROR: Missing setting MAX_COOLER_POWER
#endif
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCOOLER)
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCHAMBER) || ENABLED(PIDTEMPCOOLER)
#if DISABLED(MAX_OVERSHOOT_PID_AUTOTUNE)
#error DEPENDENCY ERROR: Missing setting MAX_OVERSHOOT_PID_AUTOTUNE
#endif
......@@ -240,6 +257,21 @@
#error DEPENDENCY ERROR: Missing setting DEFAULT_bedKd
#endif
#endif
#if ENABLED(PIDTEMPCHAMBER)
#if DISABLED(PID_CHAMBER_INTEGRAL_DRIVE_MAX)
#error DEPENDENCY ERROR: Missing setting PID_CHAMBER_INTEGRAL_DRIVE_MAX
#endif
#if DISABLED(DEFAULT_chamberKp)
#error DEPENDENCY ERROR: Missing setting DEFAULT_chamberKp
#endif
#if DISABLED(DEFAULT_chamberKi)
#error DEPENDENCY ERROR: Missing setting DEFAULT_chamberKi
#endif
#if DISABLED(DEFAULT_chamberKd)
#error DEPENDENCY ERROR: Missing setting DEFAULT_chamberKd
#endif
#endif
#if ENABLED(PIDTEMPCOOLER)
#if DISABLED(PID_COOLER_INTEGRAL_DRIVE_MAX)
#error DEPENDENCY ERROR: Missing setting PID_COOLER_INTEGRAL_DRIVE_MAX
......@@ -253,7 +285,6 @@
#if DISABLED(DEFAULT_coolerKd)
#error DEPENDENCY ERROR: Missing setting DEFAULT_coolerKd
#endif
#endif
#if ENABLED(BED_LIMIT_SWITCHING)
#if DISABLED(BED_HYSTERESIS)
......@@ -263,6 +294,14 @@
#error DEPENDENCY ERROR: Missing setting BED_CHECK_INTERVAL
#endif
#endif
#if ENABLED(CHAMBER_LIMIT_SWITCHING)
#if DISABLED(CHAMBER_HYSTERESIS)
#error DEPENDENCY ERROR: Missing setting CHAMBER_HYSTERESIS
#endif
#if DISABLED(CHAMBER_CHECK_INTERVAL)
#error DEPENDENCY ERROR: Missing setting CHAMBER_CHECK_INTERVAL
#endif
#endif
#if ENABLED(COOLER_LIMIT_SWITCHING)
#if DISABLED(COOLER_HYSTERESIS)
#error DEPENDENCY ERROR: Missing setting COOLER_HYSTERESIS
......@@ -271,7 +310,6 @@
#error DEPENDENCY ERROR: Missing setting COOLER_CHECK_INTERVAL
#endif
#endif
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
#if DISABLED(THERMAL_PROTECTION_PERIOD)
#error DEPENDENCY ERROR: Missing setting THERMAL_PROTECTION_PERIOD
......@@ -1820,36 +1858,27 @@
#error DEPENDENCY ERROR: You must set EXTRUDERS = 2 for DONDOLO
#endif
#if ENABLED(LASERBEAM) && (!PIN_EXISTS(LASER_PWR) || !PIN_EXISTS(LASER_TTL))
#error DEPENDENCY ERROR: You have to set LASER_PWR_PIN and LASER_TTL_PIN to a valid pin if you enable LASERBEAM
#endif
#if ENABLED(LASERBEAM) && ENABLED(LASER)
#error DEPENDENCY ERROR: You must enable only one of LASERBEAM or LASER, not both!
#endif
#if ENABLED(LASER)
#if ENABLED(LASERBEAM)
#if (!ENABLED(LASER_REMAP_INTENSITY) && ENABLED(LASER_RASTER))
#error DEPENDENCY ERROR: You have to set LASER_REMAP_INTENSITY with LASER_RASTER enabled
#endif
#if (!ENABLED(LASER_CONTROL) || ((LASER_CONTROL > 0) && (LASER_CONTROL < 2)))
#if (!ENABLED(LASER_CONTROL) || ((LASER_CONTROL != 1) && (LASER_CONTROL != 2)))
#error DEPENDENCY ERROR: You have to set LASER_CONTROL to 1 or 2
#else
#if(LASER_CONTROL == 1)
#if( !PIN_EXISTS(LASER_FIRING))
#error DEPENDENCY ERROR: You have to set LASER_FIRING_PIN
#if( !PIN_EXISTS(LASER_PWR))
#error DEPENDENCY ERROR: You have to set LASER_PWR_PIN
#endif
#else
#if( !PIN_EXISTS(LASER_FIRING) || !PIN_EXISTS(LASER_INTENSITY))
#error DEPENDENCY ERROR: You have to set LASER_FIRING_PIN and LASER_INTENSITY_PIN to a valid pin if you enable LASER
#endif
#if( !PIN_EXISTS(LASER_PWR) || !PIN_EXISTS(LASER_TTL))
#error DEPENDENCY ERROR: You have to set LASER_PWR_PIN and LASER_TTL_PIN to a valid pin if you enable LASER
#endif
#endif
#endif
#if DISABLED(LASER_HAS_FOCUS)
#error DEPENDENCY ERROR: Missing LASER_HAS_FOCUS setting
#endif
#endif
#if ENABLED(FILAMENT_RUNOUT_SENSOR) && !PIN_EXISTS(FILRUNOUT)
#error DEPENDENCY ERROR: You have to set FILRUNOUT_PIN to a valid pin if you enable FILAMENT_RUNOUT_SENSOR
......@@ -1895,8 +1924,4 @@
#error DEPENDENCY ERROR: You have to set SLED_PIN to a valid pin if you enable Z_PROBE_SLED
#endif
#if ENABLED(LASERBEAM) && ENABLED(LASER)
#error DEPENDENCY ERROR: You have to select only one of LASER or LASERBEAM
#endif
#endif //SANITYCHECK_H
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* flowmeter.h - Flowmeter control library for Arduino - Version 1
* Copyright (c) 2016 Franco (nextime) Lanza. All right reserved.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#include "../../base.h"
#include <Arduino.h>
#if ENABLED(FLOWMETER_SENSOR)
volatile int flowrate_pulsecount;
float flowrate;
static millis_t flowmeter_timer = 0;
static millis_t lastflow = 0;
void flowrate_pulsecounter();
void flow_init() {
flowrate = 0;
flowrate_pulsecount = 0;
pinMode(FLOWMETER_PIN, INPUT);
attachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN), flowrate_pulsecounter, FALLING);
}
void flowrate_manage() {
millis_t now;
now = millis();
if(ELAPSED(now, flowmeter_timer)) {
detachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN));
flowrate = (float)(((1000.0 / (float)((float)now - (float)lastflow)) * (float)flowrate_pulsecount) / (float)FLOWMETER_CALIBRATION);
#if ENABLED(FLOWMETER_DEBUG)
ECHO_M(" FLOWMETER DEBUG ");
ECHO_MV(" flowrate:", flowrate);
ECHO_MV(" flowrate_pulsecount:", flowrate_pulsecount);
ECHO_EMV(" CALIBRATION:", FLOWMETER_CALIBRATION);
#endif
flowmeter_timer = now + 1000UL;
lastflow = now;
flowrate_pulsecount = 0;
attachInterrupt(digitalPinToInterrupt(FLOWMETER_PIN), flowrate_pulsecounter, FALLING);
}
}
float get_flowrate() {
return flowrate;
}
void flowrate_pulsecounter() {
// Increment the pulse counter
flowrate_pulsecount++;
}
#endif // FLOWMETER_SENSOR
/**
* MK & MK4due 3D Printer Firmware
*
* Based on Marlin, Sprinter and grbl
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (C) 2013 - 2016 Alberto Cotronei @MagoKimbra
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
*/
/**
* flowmeter.h - Flowmeter control library for Arduino - Version 1
* Copyright (c) 2016 Franco (nextime) Lanza. All right reserved.
*
* This library is free software; you can redistribute it and/or
* modify it under the terms of the GNU Lesser General Public
* License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public
* License along with this library; if not, write to the Free Software
* Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/
#ifndef FLOWMETER_H
#define FLOWMETER_H
#define FLOWMETER_CALIBRATION (FLOWMETER_MAXFREQ / FLOWMETER_MAXFLOW)
#if ENABLED(FLOWMETER_SENSOR)
void flowrate_manage();
void flow_init();
float get_flowrate();
#endif
#endif // FLOWMETER_H
......@@ -51,7 +51,7 @@
#define K2 (1.0 - K1)
#endif
#if ENABLED(PIDTEMPBED) || ENABLED(PIDTEMP) || ENABLED(PIDTEMPCOOLER)
#if ENABLED(PIDTEMPBED) || ENABLED(PIDTEMP) || ENABLED(PIDTEMPCHAMBER) || ENABLED(PIDTEMPCOOLER)
#define PID_dT ((OVERSAMPLENR * 14.0)/(F_CPU / 64.0 / 256.0))
#endif
......@@ -60,11 +60,17 @@
//===========================================================================
int target_temperature[4] = { 0 };
int target_temperature_bed = 0;
int current_temperature_raw[4] = { 0 };
float current_temperature[4] = { 0.0 };
int current_temperature_bed_raw = 0;
int current_temperature_raw[4] = { 0 };
int target_temperature_bed = 0;
float current_temperature_bed = 0.0;
int current_temperature_bed_raw = 0;
int target_temperature_chamber = 0;
int current_temperature_chamber_raw = 0;
float current_temperature_chamber = 0.0;
int target_temperature_cooler = 0;
int current_temperature_cooler_raw = 0;
float current_temperature_cooler = 0.0;
......@@ -78,7 +84,13 @@ float current_temperature_cooler = 0.0;
float bedKp = DEFAULT_bedKp;
float bedKi = ((DEFAULT_bedKi) * (PID_dT));
float bedKd = ((DEFAULT_bedKd) / (PID_dT));
#endif //PIDTEMPBED
#endif
#if ENABLED(PIDTEMPCHAMBER)
float chamberKp = DEFAULT_chamberKp;
float chamberKi = ((DEFAULT_chamberKi) * (PID_dT));
float chamberKd = ((DEFAULT_chamberKd) / (PID_dT));
#endif
#if ENABLED(PIDTEMPCOOLER)
float coolerKp = DEFAULT_coolerKp;
......@@ -97,14 +109,15 @@ float current_temperature_cooler = 0.0;
#endif
unsigned char soft_pwm_bed;
unsigned char soft_pwm_chamber;
unsigned char soft_pwm_cooler;
#if ENABLED(FAST_PWM_COOLER)
unsigned char fast_pwm_cooler;
#endif
void setPwmCooler(unsigned char pwm);
#if ENABLED(BABYSTEPPING)
volatile int babystepsTodo[3] = { 0 };
#endif
......@@ -114,7 +127,7 @@ void setPwmCooler(unsigned char pwm);
#endif
#if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED) || ENABLED(THERMAL_PROTECTION_COOLER)
enum TRState { TRInactive, TRFirstRunnig, TRStable, TRRunaway };
enum TRState { TRInactive, TRFirstRunning, TRStable, TRRunaway };
void thermal_runaway_protection(TRState* state, millis_t* timer, float temperature, float target_temperature, int temp_controller_id, int period_seconds, int hysteresis_degc);
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
......@@ -172,9 +185,23 @@ static volatile bool temp_meas_ready = false;
static float pid_error_bed;
static float temp_iState_min_bed;
static float temp_iState_max_bed;
#else //PIDTEMPBED
#else // PIDTEMPBED
static millis_t next_bed_check_ms;
#endif //PIDTEMPBED
#endif // !PIDTEMPBED
#if ENABLED(PIDTEMPCHAMBER)
//static cannot be external:
static float temp_iState_chamber = { 0 };
static float temp_dState_chamber = { 0 };
static float pTerm_chamber;
static float iTerm_chamber;
static float dTerm_chamber;
//int output;
static float pid_error_chamber;
static float temp_iState_min_chamber;
static float temp_iState_max_chamber;
#else // PIDTEMPCHAMBER
static millis_t next_chamber_check_ms;
#endif // !PIDTEMPCHAMBER
#if ENABLED(PIDTEMPCOOLER)
//static cannot be external:
static float temp_iState_cooler = { 0 };
......@@ -186,9 +213,9 @@ static volatile bool temp_meas_ready = false;
static float pid_error_cooler;
static float temp_iState_min_cooler;
static float temp_iState_max_cooler;
#else
#else // PIDTEMPCOOLER
static millis_t next_cooler_check_ms;
#endif
#endif // !PIDTEMPCOOLER
static unsigned char soft_pwm[HOTENDS];
......@@ -209,7 +236,6 @@ static unsigned char soft_pwm[HOTENDS];
float Kp[HOTENDS], Ki[HOTENDS], Kd[HOTENDS], Kc[HOTENDS];
#endif //PIDTEMP
// Init min and max temp with extreme values to prevent false errors during startup
static int minttemp_raw[HOTENDS] = ARRAY_BY_HOTENDS( HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP, HEATER_3_RAW_LO_TEMP);
static int maxttemp_raw[HOTENDS] = ARRAY_BY_HOTENDS( HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP, HEATER_3_RAW_HI_TEMP);
......@@ -221,6 +247,12 @@ static int maxttemp[HOTENDS] = ARRAY_BY_HOTENDS1(16383);
#if ENABLED(BED_MAXTEMP)
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
#endif
#if ENABLED(CHAMBER_MINTEMP)
static int chamber_minttemp_raw = HEATER_CHAMBER_RAW_LO_TEMP;
#endif
#if ENABLED(CHAMBER_MAXTEMP)
static int chamber_maxttemp_raw = HEATER_CHAMBER_RAW_HI_TEMP;
#endif
#if ENABLED(COOLER_MINTEMP)
static int cooler_minttemp_raw = COOLER_RAW_LO_TEMP;
#endif
......@@ -238,6 +270,7 @@ static int maxttemp[HOTENDS] = ARRAY_BY_HOTENDS1(16383);
static float analog2temp(int raw, uint8_t e);
static float analog2tempBed(int raw);
static float analog2tempChamber(int raw);
static float analog2tempCooler(int raw);
static void updateTemperaturesFromRawValues();
......@@ -246,16 +279,21 @@ static void updateTemperaturesFromRawValues();
millis_t watch_heater_next_ms[HOTENDS] = { 0 };
#endif
#if ENABLED(THERMAL_PROTECTION_COOLER)
int watch_target_temp_cooler = 0;
millis_t watch_cooler_next_ms = 0;
#endif
#if ENABLED(THERMAL_PROTECTION_BED)
int watch_target_bed_temp = 0;
millis_t watch_bed_next_ms = 0;
#endif
#if ENABLED(THERMAL_PROTECTION_CHAMBER)
int watch_target_temp_chamber = 0;
millis_t watch_chamber_next_ms = 0;
#endif
#if ENABLED(THERMAL_PROTECTION_COOLER)
int watch_target_temp_cooler = 0;
millis_t watch_cooler_next_ms = 0;
#endif
#if DISABLED(SOFT_PWM_SCALE)
#define SOFT_PWM_SCALE 0
#endif
......@@ -272,18 +310,15 @@ static void updateTemperaturesFromRawValues();
//================================ Functions ================================
//===========================================================================
void setPwmCooler(unsigned char pwm) {
soft_pwm_cooler = pwm >> 1;
#if ENABLED(FAST_PWM_COOLER)
fast_pwm_cooler = pwm;
analogWrite(COOLER_PIN, pwm);
#endif
}
unsigned char getPwmCooler(bool soft=true) {
unsigned char getPwmCooler(bool soft = true) {
if(soft)
return soft_pwm_cooler;
#if ENABLED(FAST_PWM_COOLER)
......@@ -325,9 +360,9 @@ void autotempShutdown() {
#if HASNT(TEMP_BED) && HASNT(TEMP_COOLER)
|| temp_controller < 0
#elif HASNT(TEMP_BED)
|| (temp_controller == -1 && temp_controller < -2)
|| (temp_controller == -1 && temp_controller < -3)
#elif HASNT(TEMP_COOLER)
|| temp_controller < -1
|| temp_controller < -2
#endif
) {
ECHO_LM(ER, SERIAL_PID_BAD_TEMP_CONTROLLER_NUM);
......@@ -338,7 +373,10 @@ void autotempShutdown() {
if (temp_controller == -1) {
ECHO_SM(DB, "BED");
}
else if(temp_controller < -1) {
else if(temp_controller == -2) {
ECHO_SM(DB, "CHAMBER");
}
else if(temp_controller == -3) {
ECHO_SM(DB, "COOLER");
}
else {
......@@ -352,7 +390,7 @@ void autotempShutdown() {
if (temp_controller == -1)
soft_pwm_bed = bias = d = MAX_BED_POWER / 2;
else if(temp_controller < -1) {
else if (temp_controller == -3) {
bias = d = MAX_COOLER_POWER / 2;
setPwmCooler(MAX_COOLER_POWER);
}
......@@ -367,9 +405,9 @@ void autotempShutdown() {
if (temp_meas_ready) { // temp sample ready
updateTemperaturesFromRawValues();
if(temp_controller == -1)
if (temp_controller == -1)
input = current_temperature_bed;
else if(temp_controller < -1)
else if (temp_controller == -3)
input = current_temperature_cooler;
else
input = current_temperature[temp_controller];
......@@ -387,15 +425,18 @@ void autotempShutdown() {
if (running && ((input > temp && temp_controller >= -1) || (input < temp && temp_controller < -1))) {
if (ms > t2 + 5000UL) {
running = false;
if (temp_controller < -1)
if (temp_controller == -3)
setPwmCooler((bias - d));
else if (temp_controller < 0)
else if (temp_controller == -1)
soft_pwm_bed = (bias - d) >> 1;
else
soft_pwm[temp_controller] = (bias - d) >> 1;
t1 = ms;
t_high = t1 - t2;
if (temp_controller < -1)
if (temp_controller == -3)
min = temp;
else
max = temp;
......@@ -409,10 +450,12 @@ void autotempShutdown() {
t_low = t2 - t1;
if (cycles > 0) {
long max_pow;
if (temp_controller < -1)
if (temp_controller == -3)
max_pow = MAX_COOLER_POWER;
else
max_pow = temp_controller < 0 ? MAX_BED_POWER : PID_MAX;
bias += (d * (t_high - t_low)) / (t_low + t_high);
bias = constrain(bias, 20, max_pow - 20);
d = (bias > max_pow / 2) ? max_pow - 1 - bias : bias;
......@@ -439,20 +482,25 @@ void autotempShutdown() {
ECHO_E;
}
}
#if ENABLED(PIDTEMP)
if (temp_controller >= 0)
soft_pwm[temp_controller] = (bias + d) >> 1;
#endif
#if ENABLED(PIDTEMPBED)
if (temp_controller == -1)
soft_pwm_bed = (bias + d) >> 1;
#endif
#if ENABLED(PIDTEMPCOOLER)
if (temp_controller < -1)
if (temp_controller == -3)
setPwmCooler((bias + d));
#endif
cycles++;
if(temp_controller < -1)
if(temp_controller == -3)
max = temp;
else
min = temp;
......@@ -473,8 +521,12 @@ void autotempShutdown() {
print_heaterstates();
ECHO_E;
#endif
#if HAS(TEMP_CHAMBER)
print_chamberstate();
ECHO_E;
#endif
#if HAS(TEMP_COOLER)
print_coolerstates();
print_coolerstate();
ECHO_E;
#endif
......@@ -488,6 +540,7 @@ void autotempShutdown() {
}
if (cycles > ncycles) {
ECHO_LM(DB, SERIAL_PID_AUTOTUNE_FINISHED);
#if ENABLED(PIDTEMP)
if (temp_controller >= 0) {
ECHO_SMV(DB, SERIAL_KP, PID_PARAM(Kp, temp_controller));
......@@ -501,8 +554,9 @@ void autotempShutdown() {
}
}
#endif
#if ENABLED(PIDTEMPBED)
if(temp_controller == -1) {
if (temp_controller == -1) {
ECHO_LMV(DB, "#define DEFAULT_bedKp ", workKp);
ECHO_LMV(DB, "#define DEFAULT_bedKi ", unscalePID_i(workKi));
ECHO_LMV(DB, "#define DEFAULT_bedKd ", unscalePID_d(workKd));
......@@ -514,8 +568,9 @@ void autotempShutdown() {
}
}
#endif
#if ENABLED(PIDTEMPCOOLER)
if(temp_controller < -1) {
if (temp_controller == -3) {
ECHO_LMV(DB, "#define DEFAULT_coolerKp ", workKp);
ECHO_LMV(DB, "#define DEFAULT_coolerKi ", unscalePID_i(workKi));
ECHO_LMV(DB, "#define DEFAULT_coolerKd ", unscalePID_d(workKd));
......@@ -547,13 +602,24 @@ void updatePID() {
#if ENABLED(PIDTEMPBED)
temp_iState_max_bed = PID_BED_INTEGRAL_DRIVE_MAX / bedKi;
#endif
#if ENABLED(PIDTEMPCHAMBER)
temp_iState_max_chamber = PID_CHAMBER_INTEGRAL_DRIVE_MAX / chamberKi;
#endif
#if ENABLED(PIDTEMPCOOLER)
temp_iState_max_cooler = PID_COOLER_INTEGRAL_DRIVE_MAX / coolerKi;
#endif
}
int getHeaterPower(int heater) {
return heater < 0 ? soft_pwm_bed : soft_pwm[heater];
return soft_pwm[heater];
}
int getBedPower() {
return soft_pwm_bed;
}
int getChamberPower() {
return soft_pwm_chamber;
}
int getCoolerPower() {
......@@ -565,8 +631,7 @@ int getCoolerPower() {
}
#if HAS(AUTO_FAN)
void setExtruderAutoFanState(int pin, bool state) {
void setExtruderAutoFanState(int pin, bool state) {
unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : EXTRUDER_AUTO_FAN_MIN_SPEED;
// this idiom allows both digital and PWM fan outputs (see M42 handling).
#if ENABLED(FAN_SOFT_PWM)
......@@ -575,9 +640,9 @@ void setExtruderAutoFanState(int pin, bool state) {
digitalWrite(pin, newFanSpeed);
analogWrite(pin, newFanSpeed);
#endif
}
}
void checkExtruderAutoFans() {
void checkExtruderAutoFans() {
uint8_t fanState = 0;
// which fan pins need to be turned on?
......@@ -635,8 +700,7 @@ void checkExtruderAutoFans() {
&& EXTRUDER_3_AUTO_FAN_PIN != EXTRUDER_2_AUTO_FAN_PIN)
setExtruderAutoFanState(EXTRUDER_3_AUTO_FAN_PIN, (fanState & 8) != 0);
#endif
}
}
#endif // HAS(AUTO_FAN)
//
......@@ -651,15 +715,19 @@ inline void _temp_error(int tc, const char* serial_msg, const char* lcd_msg) {
ECHO_EV((int)tc);
}
else if (tc == -1) {
ECHO_M(SERIAL_STOPPED_HEATER);
ECHO_EM(SERIAL_HEATER_BED);
ECHO_EM(SERIAL_STOPPED_BED);
}
else if (tc == -2) {
ECHO_EM(SERIAL_STOPPED_CHAMBER);
}
else
ECHO_EM(SERIAL_STOPPED_COOLER);
#if ENABLED(ULTRA_LCD)
lcd_setalertstatuspgm(lcd_msg);
#endif
}
#if DISABLED(BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE)
if (!killed) {
Running = false;
......@@ -805,7 +873,47 @@ float get_pid_output(int h) {
ECHO_MV(" pTerm ", pTerm_bed);
ECHO_MV(" iTerm ", iTerm_bed);
ECHO_EMV(" dTerm ", dTerm_bed);
#endif //PID_BED_DEBUG
#endif // PID_BED_DEBUG
return pid_output;
}
#endif
#if ENABLED(PIDTEMPCHAMBER)
float get_pid_output_chamber() {
float pid_output;
#if ENABLED(PID_OPENLOOP)
pid_output = constrain(target_temperature_chamber, 0, MAX_CHAMBER_POWER);
#else
pid_error_chamber = target_temperature_chamber - current_temperature_chamber;
pTerm_chamber = bedKp * pid_error_chamber;
temp_iState_chamber += pid_error_chamber;
temp_iState_chamber = constrain(temp_iState_chamber, temp_iState_min_chamber, temp_iState_max_chamber);
iTerm_chamber = chamberKi * temp_iState_chamber;
dTerm_chamber = K2 * chamberKd * (current_temperature_chamber - temp_dState_chamber) + K1 * dTerm_chamber;
temp_dState_chamber = current_temperature_chamber;
pid_output = pTerm_chamber + iTerm_chamber - dTerm_chamber;
if (pid_output > MAX_CHAMBER_POWER) {
if (pid_error_chamber > 0) temp_iState_chamber -= pid_error_chamber; // conditional un-integration
pid_output = MAX_CHAMBER_POWER;
}
else if (pid_output < 0) {
if (pid_error_chamber < 0) temp_iState_chamber -= pid_error_chamber; // conditional un-integration
pid_output = 0;
}
#endif // PID_OPENLOOP
#if ENABLED(PID_CHAMBER_DEBUG)
ECHO_SM(DB ," PID_CHAMBER_DEBUG ");
ECHO_MV(": Input ", current_temperature_chamber);
ECHO_MV(" Output ", pid_output);
ECHO_MV(" pTerm ", pTerm_chamber);
ECHO_MV(" iTerm ", iTerm_chamber);
ECHO_EMV(" dTerm ", dTerm_chamber);
#endif // PID_CHAMBER_DEBUG
return pid_output;
}
......@@ -816,7 +924,7 @@ float get_pid_output(int h) {
float pid_output;
// We need this cause 0 is lower than our current temperature probably.
if(target_temperature_cooler < COOLER_MINTEMP)
if (target_temperature_cooler < COOLER_MINTEMP)
return 0.0;
#if ENABLED(PID_OPENLOOP)
......@@ -859,7 +967,7 @@ float get_pid_output(int h) {
#endif
/**
* Manage heating activities for extruder hot-ends and a heated bed
* Manage heating activities for hotends, bed, chamber and cooler
* - Acquire updated temperature readings
* - Invoke thermal runaway protection
* - Manage extruder auto-fan
......@@ -878,7 +986,7 @@ void manage_temp_controller() {
if (ct < max(HEATER_0_MINTEMP, 0.01)) min_temp_error(0);
#endif
#if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED) || ENABLED(THERMAL_PROTECTION_COOLER) || DISABLED(PIDTEMPBED) || DISABLED(PIDTEMPCOOLER) || HAS(AUTO_FAN)
#if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED) || ENABLED(THERMAL_PROTECTION_CHAMBER) || ENABLED(THERMAL_PROTECTION_COOLER) || DISABLED(PIDTEMPBED) || DISABLED(PIDTEMPCHAMBER) || DISABLED(PIDTEMPCOOLER) || HAS(AUTO_FAN)
millis_t ms = millis();
#endif
......@@ -958,20 +1066,24 @@ void manage_temp_controller() {
NOLESS(vm, 0.01);
volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM] = vm;
}
#endif //FILAMENT_SENSOR
#endif // FILAMENT_SENSOR
#if DISABLED(PIDTEMPBED)
#if HAS(TEMP_BED) && DISABLED(PIDTEMPBED)
if (ms < next_bed_check_ms) return;
next_bed_check_ms = ms + BED_CHECK_INTERVAL;
#endif
#if DISABLED(PIDTEMPCOOLER)
#if HAS(TEMP_CHAMBER) && DISABLED(PIDTEMPCHAMBER)
if (ms < next_chamber_check_ms) return;
next_chamber_check_ms = ms + CHAMBER_CHECK_INTERVAL;
#endif
#if HAS(TEMP_COOLER) && DISABLED(PIDTEMPCOOLER)
if (ms < next_cooler_check_ms) return;
next_cooler_check_ms = ms + COOLER_CHECK_INTERVAL;
#endif
#if TEMP_SENSOR_BED != 0
#if HAS(TEMP_BED)
#if ENABLED(THERMAL_PROTECTION_BED)
thermal_runaway_protection(&thermal_runaway_bed_state_machine, &thermal_runaway_bed_timer, current_temperature_bed, target_temperature_bed, -1, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS);
#endif
......@@ -1003,10 +1115,43 @@ void manage_temp_controller() {
WRITE_HEATER_BED(LOW);
}
#endif
#endif // TEMP_SENSOR_BED != 0
#endif // HAS(TEMP_BED)
#if TEMP_SENSOR_COOLER != 0
#if HAS(TEMP_CHAMBER)
#if ENABLED(THERMAL_PROTECTION_CHAMBER)
thermal_runaway_protection(&thermal_runaway_chamber_state_machine, &thermal_runaway_chamber_timer, current_temperature_chamber, target_temperature_chamber, -1, THERMAL_PROTECTION_CHAMBER_PERIOD, THERMAL_PROTECTION_CHAMBER_HYSTERESIS);
#endif
#if ENABLED(PIDTEMPCHAMBER)
float pid_output = get_pid_output_chamber();
soft_pwm_chamber = current_temperature_chamber > CHAMBER_MINTEMP && current_temperature_chamber < CHAMBER_MAXTEMP ? (int)pid_output >> 1 : 0;
#elif ENABLED(CHAMBER_LIMIT_SWITCHING)
// Check if temperature is within the correct band
if (current_temperature_chamber > CHAMBER_MINTEMP && current_temperature_chamber < CHAMBER_MAXTEMP) {
if (current_temperature_chamber >= target_temperature_chamber + CHAMBER_HYSTERESIS)
soft_pwm_chamber = 0;
else if (current_temperature_chamber <= target_temperature_chamber - CHAMBER_HYSTERESIS)
soft_pwm_chamber = MAX_CHAMBER_POWER >> 1;
}
else {
soft_pwm_chamber = 0;
WRITE_HEATER_CHAMBER(LOW);
}
#else // !PIDTEMPCHAMBER && !CHAMBER_LIMIT_SWITCHING
// Check if temperature is within the correct range
if (current_temperature_chamber > CHAMBER_MINTEMP && current_temperature_chamber < CHAMBER_MAXTEMP) {
soft_pwm_chamber = current_temperature_chamber < target_temperature_chamber ? MAX_CHAMBER_POWER >> 1 : 0;
}
else {
soft_pwm_chamber = 0;
WRITE_HEATER_CHAMBER(LOW);
}
#endif
#endif // HAS(TEMP_CHAMBER)
#if HAS(TEMP_COOLER)
#if ENABLED(THERMAL_PROTECTION_COOLER)
thermal_runaway_protection(&thermal_runaway_cooler_state_machine, &thermal_runaway_cooler_timer, current_temperature_cooler, target_temperature_cooler, -2, THERMAL_PROTECTION_COOLER_PERIOD, THERMAL_PROTECTION_COOLER_HYSTERESIS);
#endif
......@@ -1038,8 +1183,7 @@ void manage_temp_controller() {
WRITE_COOLER(LOW);
}
#endif
#endif // TEMP_SENSOR_COOLER != 0
#endif // HAS(TEMP_COOLER)
}
#define PGM_RD_W(x) (short)pgm_read_word(&x)
......@@ -1117,7 +1261,7 @@ static float analog2tempBed(int raw) {
#elif ENABLED(BED_USES_AD595)
#ifdef __SAM3X8E__
return ((raw * ((3.3 * 100.0) / 1024.0) / OVERSAMPLENR) * ad595_gain[h]) + ad595_offset[h];
return ((raw * ((3.3 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#else
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#endif
......@@ -1128,6 +1272,37 @@ static float analog2tempBed(int raw) {
#endif
}
static float analog2tempChamber(int raw) {
#if ENABLED(CHAMBER_USES_THERMISTOR)
float celsius = 0;
byte i;
for (i = 1; i < CHAMBERTEMPTABLE_LEN; i++) {
if (PGM_RD_W(CHAMBERTEMPTABLE[i][0]) > raw) {
celsius = PGM_RD_W(CHAMBERTEMPTABLE[i - 1][1]) +
(raw - PGM_RD_W(CHAMBERTEMPTABLE[i - 1][0])) *
(float)(PGM_RD_W(CHAMBERTEMPTABLE[i][1]) - PGM_RD_W(CHAMBERTEMPTABLE[i - 1][1])) /
(float)(PGM_RD_W(CHAMBERTEMPTABLE[i][0]) - PGM_RD_W(CHAMBERTEMPTABLE[i - 1][0]));
break;
}
}
// Overflow: Set to last value in the table
if (i == CHAMBERTEMPTABLE_LEN) celsius = PGM_RD_W(CHAMBERTEMPTABLE[i - 1][1]);
return celsius;
#elif ENABLED(CHAMBER_USES_AD595)
#ifdef __SAM3X8E__
return ((raw * ((3.3 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#else
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#endif
#else
UNUSED(raw);
return 0;
#endif
}
static float analog2tempCooler(int raw) {
#if ENABLED(COOLER_USES_THERMISTOR)
......@@ -1151,14 +1326,13 @@ static float analog2tempCooler(int raw) {
#elif ENABLED(COOLER_USES_AD595)
#ifdef __SAM3X8E__
return ((raw * ((3.3 * 100.0) / 1024.0) / OVERSAMPLENR) * ad595_gain[h]) + ad595_offset[h];
return ((raw * ((3.3 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#else
return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
#endif
#else
UNUSED(raw);
return 0;
#endif
}
......@@ -1170,11 +1344,17 @@ static void updateTemperaturesFromRawValues() {
#if ENABLED(HEATER_0_USES_MAX6675)
current_temperature_raw[0] = read_max6675();
#endif
for (uint8_t h = 0; h < HOTENDS; h++) {
current_temperature[h] = analog2temp(current_temperature_raw[h], h);
}
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
current_temperature_chamber = analog2tempChamber(current_temperature_chamber_raw);
current_temperature_cooler = analog2tempCooler(current_temperature_cooler_raw);
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
redundant_temperature = analog2temp(redundant_temperature_raw, 1);
#endif
......@@ -1211,7 +1391,6 @@ static void updateTemperaturesFromRawValues() {
#if ENABLED(FILAMENT_SENSOR)
// Convert raw Filament Width to millimeters
float analog2widthFil() {
return current_raw_filwidth / 16383.0 * 5.0;
......@@ -1225,7 +1404,6 @@ static void updateTemperaturesFromRawValues() {
else NOMORE(temp, MEASURED_UPPER_LIMIT);
return filament_width_nominal / temp * 100;
}
#endif
#if HAS(POWER_CONSUMPTION_SENSOR)
......@@ -1239,11 +1417,13 @@ static void updateTemperaturesFromRawValues() {
float rel_raw_power = (current_raw_powconsumption < power_zero_raw) ? (2 * power_zero_raw - current_raw_powconsumption) : (current_raw_powconsumption);
return ((5.0 * rel_raw_power) / (1023.0 * OVERSAMPLENR)) - POWER_ZERO;
}
float analog2current() {
float temp = analog2voltage() / POWER_SENSITIVITY;
temp = (((100 - POWER_ERROR) / 100) * temp) - POWER_OFFSET;
return temp > 0 ? temp : 0;
}
float analog2power() {
return (analog2current() * POWER_VOLTAGE * 100) / POWER_EFFICIENCY;
}
......@@ -1255,6 +1435,7 @@ static void updateTemperaturesFromRawValues() {
if(temp2 <= 0) return 0.0;
return ((temp2/temp1) - 1) * 100;
}
float analog2efficiency(float watt) {
return (analog2current() * POWER_VOLTAGE * 100) / watt;
}
......@@ -1279,15 +1460,22 @@ void tp_init() {
temp_iState_min[h] = 0.0;
temp_iState_max[h] = PID_INTEGRAL_DRIVE_MAX / PID_PARAM(Ki, h);
#endif //PIDTEMP
}
#if ENABLED(PIDTEMPBED)
temp_iState_min_bed = 0.0;
temp_iState_max_bed = PID_BED_INTEGRAL_DRIVE_MAX / bedKi;
#endif // PIDTEMPBED
#if ENABLED(PIDTEMPCHAMBER)
temp_iState_min_chamber = 0.0;
temp_iState_max_chamber = PID_CHAMBER_INTEGRAL_DRIVE_MAX / chamberKi;
#endif
#if ENABLED(PIDTEMPCOOLER)
temp_iState_min_cooler = 0.0;
temp_iState_max_cooler = PID_COOLER_INTEGRAL_DRIVE_MAX / coolerKi;
#endif
}
#if ENABLED(PID_ADD_EXTRUSION_RATE)
for (int e = 0; e < EXTRUDERS; e++) last_position[e] = 0;
......@@ -1308,7 +1496,10 @@ void tp_init() {
#if HAS(HEATER_BED)
SET_OUTPUT(HEATER_BED_PIN);
#endif
#if HAS(COOLER_DEV)
#if HAS(HEATER_CHAMBER)
SET_OUTPUT(HEATER_CHAMBER_PIN);
#endif
#if HAS(COOLER)
SET_OUTPUT(COOLER_PIN);
#if ENABLED(FAST_PWM_COOLER)
setPwmFrequency(COOLER_PIN, 2); // No prescaling. Pwm frequency = F_CPU/256/64
......@@ -1363,6 +1554,9 @@ void tp_init() {
#if HAS(TEMP_BED)
ANALOG_SELECT(TEMP_BED_PIN);
#endif
#if HAS(TEMP_CHAMBER)
ANALOG_SELECT(TEMP_CHAMBER_PIN);
#endif
#if HAS(TEMP_COOLER)
ANALOG_SELECT(TEMP_COOLER_PIN);
#endif
......@@ -1489,6 +1683,26 @@ void tp_init() {
#endif
}
#endif // BED_MAXTEMP
#if ENABLED(CHAMBER_MINTEMP)
while(analog2tempChamber(chamber_minttemp_raw) < CHAMBER_MINTEMP) {
#if CHAMBER_RAW_LO_TEMP < HEATER_CHAMBER_RAW_HI_TEMP
chamber_minttemp_raw += OVERSAMPLENR;
#else
chamber_minttemp_raw -= OVERSAMPLENR;
#endif
}
#endif // CHAMBER_MINTEMP
#if ENABLED(CHAMBER_MAXTEMP)
while(analog2tempCooler(chamber_maxttemp_raw) > CHAMBER_MAXTEMP) {
#if CHAMBER_RAW_LO_TEMP < CHAMBER_RAW_HI_TEMP
chamber_maxttemp_raw -= OVERSAMPLENR;
#else
chamber_maxttemp_raw += OVERSAMPLENR;
#endif
}
#endif // BED_MAXTEMP
#if ENABLED(COOLER_MINTEMP)
while(analog2tempCooler(cooler_minttemp_raw) < COOLER_MINTEMP) {
#if COOLER_RAW_LO_TEMP < HEATER_COOLER_RAW_HI_TEMP
......@@ -1497,7 +1711,7 @@ void tp_init() {
cooler_minttemp_raw -= OVERSAMPLENR;
#endif
}
#endif //COOLER_MINTEMP
#endif // COOLER_MINTEMP
#if ENABLED(COOLER_MAXTEMP)
while(analog2tempCooler(cooler_maxttemp_raw) > COOLER_MAXTEMP) {
#if COOLER_RAW_LO_TEMP < COOLER_RAW_HI_TEMP
......@@ -1506,8 +1720,7 @@ void tp_init() {
cooler_maxttemp_raw += OVERSAMPLENR;
#endif
}
#endif // BED_MAXTEMP
#endif // COOLER_MAXTEMP
}
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
......@@ -1526,22 +1739,6 @@ void tp_init() {
}
#endif
#if ENABLED(THERMAL_PROTECTION_COOLER) && ENABLED(THERMAL_PROTECTION_COOLER_WATCHDOG)
/**
* Start Cooling Sanity Check for hotends that are below
* their target temperature by a configurable margin.
* This is called when the temperature is set. (M141)
*/
void start_watching_cooler() {
if (degCooler() > degTargetCooler() - (WATCH_TEMP_COOLER_DECREASE - TEMP_COOLER_HYSTERESIS - 1)) {
watch_target_temp_cooler = degCooler() - WATCH_COOLER_TEMP_DECREASE;
watch_cooler_next_ms = millis() + WATCH_TEMP_COOLER_PERIOD * 1000UL;
}
else
watch_cooler_next_ms = 0;
}
#endif
#if ENABLED(THERMAL_PROTECTION_BED)
/**
* Start Heating Sanity Check for bed that are below
......@@ -1558,12 +1755,42 @@ void tp_init() {
}
#endif
#if ENABLED(THERMAL_PROTECTION_CHAMBER)
/**
* Start Cooling Sanity Check for chamber that are below
* their target temperature by a configurable margin.
* This is called when the temperature is set. (M141)
*/
void start_watching_chamber() {
if (degCooler() > degTargetCooler() - (WATCH_TEMP_CHAMBER_DECREASE - TEMP_CHAMBER_HYSTERESIS - 1)) {
watch_target_temp_chamber = degChamber() - WATCH_CHAMBER_TEMP_DECREASE;
watch_chamber_next_ms = millis() + WATCH_TEMP_CHAMBER_PERIOD * 1000UL;
}
else
watch_chamber_next_ms = 0;
}
#endif
#if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED) || ENABLED(THERMAL_PROTECTION_COOLER)
#if ENABLED(THERMAL_PROTECTION_COOLER)
/**
* Start Cooling Sanity Check for hotends that are below
* their target temperature by a configurable margin.
* This is called when the temperature is set. (M142)
*/
void start_watching_cooler() {
if (degCooler() > degTargetCooler() - (WATCH_TEMP_COOLER_DECREASE - TEMP_COOLER_HYSTERESIS - 1)) {
watch_target_temp_cooler = degCooler() - WATCH_COOLER_TEMP_DECREASE;
watch_cooler_next_ms = millis() + WATCH_TEMP_COOLER_PERIOD * 1000UL;
}
else
watch_cooler_next_ms = 0;
}
#endif
#if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED) || ENABLED(THERMAL_PROTECTION_CHAMBER) || ENABLED(THERMAL_PROTECTION_COOLER)
void thermal_runaway_protection(TRState* state, millis_t* timer, float temperature, float target_temperature, int temp_controller_id, int period_seconds, int hysteresis_degc) {
static float tr_target_temperature[HOTENDS + 2] = { 0.0 };
static float tr_target_temperature[HOTENDS + 3] = { 0.0 };
/*
ECHO_SM(DB, "Thermal Thermal Runaway Running. Heater ID: ");
......@@ -1579,12 +1806,15 @@ void tp_init() {
temp_controller_index = temp_controller_id;
else if(temp_controller_id == -1)
temp_controller_index = HOTENDS; // BED
else:
temp_controller_index = HOTENDS + 1; // COOLER
else if(temp_controller_id == -2)
temp_controller_index = HOTENDS + 1; // CHAMBER
else
temp_controller_index = HOTENDS + 2; // COOLER
// If the target temperature changes, restart
if (tr_target_temperature[temp_controller_index] != target_temperature)
tr_target_temperature[temp_controller_index] = target_temperature;
*state = target_temperature > 0 ? TRFirstRunning : TRInactive;
switch (*state) {
......@@ -1592,36 +1822,37 @@ void tp_init() {
case TRInactive: break;
// When first heating/cooling, wait for the temperature to be reached then go to Stable state
case TRFirstRunning:
if (temperature < tr_target_temperature[temp_controller_index] && temp_controller_index > HEATERS) break;
else if((temperature > tr_target_temperature[temp_controller_index] && temp_controller_index <= HEATERS) break;
if (temperature < tr_target_temperature[temp_controller_index] && temp_controller_index > HOTENDS) break;
else if ((temperature > tr_target_temperature[temp_controller_index] && temp_controller_index <= HOTENDS)) break;
*state = TRStable;
// While the temperature is stable watch for a bad temperature
case TRStable:
if(temp_controller_index <= HEATERS) { // HEATERS
if (temp_controller_index <= HOTENDS) { // HOTENDS
if (temperature < tr_target_temperature[temp_controller_index] - hysteresis_degc && ELAPSED(millis(), *timer))
*state = TRRunaway;
else {
*timer = millis() + period_seconds * 1000UL;
break;
}
}
else { // COOLERS
if (temperature > tr_target_temperature[temp_controller_index] + hysteresis_degc && ELAPSED(millis(), *timer)))
if (temperature > tr_target_temperature[temp_controller_index] + hysteresis_degc && ELAPSED(millis(), *timer))
*state = TRRunaway;
else {
*timer = millis() + period_seconds * 1000UL;
break;
}
}
case TRRunaway:
_temp_error(temp_controller_id, PSTR(SERIAL_T_THERMAL_RUNAWAY), PSTR(MSG_THERMAL_RUNAWAY));
}
}
#endif // THERMAL_PROTECTION_HOTENDS || THERMAL_PROTECTION_BED
#endif // THERMAL_PROTECTION_HOTENDS || THERMAL_PROTECTION_BED || THERMAL_PROTECTION_CHAMBER || THERMAL_PROTECTION_COOLER
void disable_all_heaters() {
for (int i = 0; i < HOTENDS; i++) setTargetHotend(0, i);
setTargetBed(0);
setTargetChamber(0);
// If all heaters go down then for sure our print job has stopped
print_job_counter.stop();
......@@ -1657,6 +1888,14 @@ void disable_all_heaters() {
WRITE_HEATER_BED(LOW);
#endif
#endif
#if HAS(TEMP_CHAMBER)
target_temperature_chamber = 0;
soft_pwm_chamber = 0;
#if HAS(HEATER_CHAMBER)
WRITE_HEATER_CHAMBER(LOW);
#endif
#endif
}
void disable_all_coolers() {
......@@ -1673,7 +1912,7 @@ void disable_all_coolers() {
#if HAS(TEMP_COOLER)
target_temperature_cooler = 0;
setPwmCooler(0);
#if HAS(COOLER_DEV) && !ENABLED(FAST_PWM_COOLER)
#if HAS(COOLER) && !ENABLED(FAST_PWM_COOLER)
WRITE_COOLER(LOW);
#endif
#endif
......@@ -1746,6 +1985,8 @@ enum TempState {
MeasureTemp_0,
PrepareTemp_BED,
MeasureTemp_BED,
PrepareTemp_CHAMBER,
MeasureTemp_CHAMBER,
PrepareTemp_COOLER,
MeasureTemp_COOLER,
PrepareTemp_1,
......@@ -1763,9 +2004,9 @@ enum TempState {
static unsigned long raw_temp_value[4] = { 0 };
static unsigned long raw_temp_bed_value = 0;
static unsigned long raw_temp_chamber_value = 0;
static unsigned long raw_temp_cooler_value = 0;
static void set_current_temp_raw() {
#if HAS(TEMP_0) && DISABLED(HEATER_0_USES_MAX6675)
current_temperature_raw[0] = raw_temp_value[0];
......@@ -1784,6 +2025,7 @@ static void set_current_temp_raw() {
#endif
#endif
current_temperature_bed_raw = raw_temp_bed_value;
current_temperature_chamber_raw = raw_temp_chamber_value;
current_temperature_cooler_raw = raw_temp_cooler_value;
#if HAS(POWER_CONSUMPTION_SENSOR)
......@@ -1830,8 +2072,11 @@ ISR(TIMER0_COMPB_vect) {
#if HAS(HEATER_BED)
ISR_STATICS(BED);
#endif
#if HAS(COOLER_DEV) && !ENABLED(FAST_PWM_COOLER)
ISR_STATICS(COOLER_DEV);
#if HAS(HEATER_CHAMBER)
ISR_STATICS(CHAMBER);
#endif
#if HAS(COOLER) && !ENABLED(FAST_PWM_COOLER)
ISR_STATICS(COOLER);
#endif
#if HAS(FILAMENT_SENSOR)
......@@ -1866,10 +2111,17 @@ ISR(TIMER0_COMPB_vect) {
soft_pwm_BED = soft_pwm_bed;
WRITE_HEATER_BED(soft_pwm_BED > 0 ? 1 : 0);
#endif
#if HAS(COOLER_DEV) && !ENABLED(FAST_PWM_COOLER)
soft_pwm_COOLER_DEV = soft_pwm_cooler;
WRITE_COOLER(soft_pwm_COOLER_DEV > 0 ? 1 : 0);
#if HAS(HEATER_CHAMBER)
soft_pwm_CHAMBER = soft_pwm_chamber;
WRITE_HEATER_CHAMBER(soft_pwm_CHAMBER > 0 ? 1 : 0);
#endif
#if HAS(COOLER) && !ENABLED(FAST_PWM_COOLER)
soft_pwm_COOLER = soft_pwm_cooler;
WRITE_COOLER(soft_pwm_COOLER > 0 ? 1 : 0);
#endif
#if ENABLED(FAN_SOFT_PWM)
soft_pwm_fan = fanSpeedSoftPwm / 2;
#if HAS(CONTROLLERFAN)
......@@ -1909,8 +2161,13 @@ ISR(TIMER0_COMPB_vect) {
#if HAS(HEATER_BED)
if (soft_pwm_BED < pwm_count) WRITE_HEATER_BED(0);
#endif
#if HAS(COOLER_DEV) && !ENABLED(FAST_PWM_COOLER)
if (soft_pwm_COOLER_DEV < pwm_count ) WRITE_COOLER(0);
#if HAS(HEATER_CHAMBER)
if (soft_pwm_CHAMBER < pwm_count) WRITE_HEATER_CHAMBER(0);
#endif
#if HAS(COOLER) && !ENABLED(FAST_PWM_COOLER)
if (soft_pwm_COOLER < pwm_count ) WRITE_COOLER(0);
#endif
#if ENABLED(FAN_SOFT_PWM)
......@@ -1990,11 +2247,17 @@ ISR(TIMER0_COMPB_vect) {
#endif
#endif
#endif
#if HAS(HEATER_BED)
_SLOW_PWM_ROUTINE(BED, soft_pwm_bed); // BED
#endif
#if HAS(COOLER_DEV) && !ENABLED(FAST_PWM_COOLER)
_SLOW_PWM_SOURINT(COOLER_DEV, soft_pwm_cooler); // COOLER
#if HAS(HEATER_CHAMBER)
_SLOW_PWM_ROUTINE(CHAMBER, soft_pwm_chamber); // CHAMBER
#endif
#if HAS(COOLER) && !ENABLED(FAST_PWM_COOLER)
_SLOW_PWM_ROUTINE(COOLER, soft_pwm_cooler); // COOLER
#endif
} // slow_pwm_count == 0
......@@ -2009,11 +2272,17 @@ ISR(TIMER0_COMPB_vect) {
#endif
#endif
#endif
#if HAS(HEATER_BED)
PWM_OFF_ROUTINE(BED); // BED
#endif
#if HAS(COOLER_DEV) && !ENABLED(FAST_PWM_COOLER)
PWM_OFF_ROUTINE(COOLER_DEV); // COOLER
#if HAS(HEATER_CHAMBER)
PWM_OFF_ROUTINE(CHAMBER); // CHAMBER
#endif
#if HAS(COOLER) && !ENABLED(FAST_PWM_COOLER)
PWM_OFF_ROUTINE(COOLER); // COOLER
#endif
#if ENABLED(FAN_SOFT_PWM)
......@@ -2081,11 +2350,17 @@ ISR(TIMER0_COMPB_vect) {
#endif
#endif
#endif
#if HAS(HEATER_BED)
if (state_timer_heater_BED > 0) state_timer_heater_BED--;
#endif
#if HAS(COOLER_DEV) && !ENABLED(FAST_PWM_COOLER)
if(state_timer_heater_COOLER_DEV > 0) state_timer_heater_COOLER_DEV--;
#if HAS(HEATER_CHAMBER)
if (state_timer_heater_CHAMBER > 0) state_timer_heater_CHAMBER--;
#endif
#if HAS(COOLER) && !ENABLED(FAST_PWM_COOLER)
if(state_timer_heater_COOLER > 0) state_timer_heater_COOLER--;
#endif
} // (pwm_count % 64) == 0
......@@ -2125,8 +2400,23 @@ ISR(TIMER0_COMPB_vect) {
#if HAS(TEMP_BED)
raw_temp_bed_value += ADC;
#endif
temp_state = PrepareTemp_CHAMBER;
break;
case PrepareTemp_CHAMBER:
#if HAS(TEMP_CHAMBER)
START_ADC(TEMP_CHAMBER_PIN);
#endif
lcd_buttons_update();
temp_state = MeasureTemp_CHAMBER;
break;
case MeasureTemp_CHAMBER:
#if HAS(TEMP_CHAMBER)
raw_temp_chamber_value += ADC;
#endif
temp_state = PrepareTemp_COOLER;
break;
case PrepareTemp_COOLER:
#if HAS(TEMP_COOLER)
START_ADC(TEMP_COOLER_PIN);
......@@ -2140,6 +2430,7 @@ ISR(TIMER0_COMPB_vect) {
#endif
temp_state = PrepareTemp_1;
break;
case PrepareTemp_1:
#if HAS(TEMP_1)
START_ADC(TEMP_1_PIN);
......@@ -2291,6 +2582,17 @@ ISR(TIMER0_COMPB_vect) {
if (current_temperature_bed_raw GEBED bed_maxttemp_raw) _temp_error(-1, SERIAL_T_MAXTEMP, PSTR(MSG_ERR_MAXTEMP_BED));
if (bed_minttemp_raw GEBED current_temperature_bed_raw) _temp_error(-1, SERIAL_T_MINTEMP, PSTR(MSG_ERR_MINTEMP_BED));
#endif
#if HAS(TEMP_CHAMBER)
#if HEATER_CHAMBER_RAW_LO_TEMP > HEATER_CHAMBER_RAW_HI_TEMP
#define GECHAMBER <=
#else
#define GECHAMBER >=
#endif
if (current_temperature_chamber_raw GECHAMBER chamber_maxttemp_raw) _temp_error(-1, SERIAL_T_MAXTEMP, PSTR(MSG_ERR_MAXTEMP_CHAMBER));
if (chamber_minttemp_raw GECHAMBER current_temperature_chamber_raw) _temp_error(-1, SERIAL_T_MINTEMP, PSTR(MSG_ERR_MINTEMP_CHAMBER));
#endif
#if HAS(TEMP_COOLER)
#if COOLER_RAW_LO_TEMP > COOLER_RAW_HI_TEMP
#define GECOOLER <=
......@@ -2301,8 +2603,6 @@ ISR(TIMER0_COMPB_vect) {
if (cooler_minttemp_raw GECOOLER current_temperature_cooler_raw) _temp_error(-2, SERIAL_T_MINTEMP, PSTR(MSG_ERR_MINTEMP_COOLER));
#endif
} // temp_count >= OVERSAMPLENR
#if ENABLED(BABYSTEPPING)
......@@ -2321,10 +2621,10 @@ ISR(TIMER0_COMPB_vect) {
#endif //BABYSTEPPING
}
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCOOLER)
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCHAMBER) || ENABLED(PIDTEMPCOOLER)
// Apply the scale factors to the PID values
float scalePID_i(float i) { return i * PID_dT; }
float unscalePID_i(float i) { return i / PID_dT; }
float scalePID_d(float d) { return d / PID_dT; }
float unscalePID_d(float d) { return d * PID_dT; }
#endif // ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED)
#endif // ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCHAMBER) || ENABLED(PIDTEMPCOOLER)
......@@ -69,15 +69,20 @@ void manage_temp_controller(); //it is critical that this is called periodically
// do not use these routines and variables outside of temperature.cpp
extern int target_temperature[4];
extern float current_temperature[4];
extern int target_temperature_bed;
extern float current_temperature_bed;
extern int target_temperature_chamber;
extern float current_temperature_chamber;
extern int target_temperature_cooler;
extern float current_temperature_cooler;
#if ENABLED(SHOW_TEMP_ADC_VALUES)
extern int current_temperature_raw[4];
extern int current_temperature_bed_raw;
extern int current_temperature_chamber_raw;
extern int current_temperature_cooler_raw;
#endif
extern int target_temperature_bed;
extern float current_temperature_bed;
extern int target_temperature_cooler;
extern float current_temperature_cooler;
#if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
extern float redundant_temperature;
#endif
......@@ -95,11 +100,15 @@ extern float current_temperature_cooler;
extern float bedKp, bedKi, bedKd;
#endif
#if ENABLED(PIDTEMPCHAMBER)
extern float chamberKp, chamberKi, chamberKd;
#endif
#if ENABLED(PIDTEMPCOOLER)
extern float coolerKp, coolerKi, coolerKd;
#endif
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCOOLER)
#if ENABLED(PIDTEMP) || ENABLED(PIDTEMPBED) || ENABLED(PIDTEMPCHAMBER) || ENABLED(PIDTEMPCOOLER)
float scalePID_i(float i);
float scalePID_d(float d);
float unscalePID_i(float i);
......@@ -121,30 +130,37 @@ extern float current_temperature_cooler;
FORCE_INLINE float degHotend(uint8_t hotend) { return current_temperature[HOTEND_ARG]; }
FORCE_INLINE float degBed() { return current_temperature_bed; }
FORCE_INLINE float degChamber() { return current_temperature_chamber; }
FORCE_INLINE float degCooler() { return current_temperature_cooler; }
#if ENABLED(SHOW_TEMP_ADC_VALUES)
FORCE_INLINE float rawHotendTemp(uint8_t hotend) { return current_temperature_raw[HOTEND_ARG]; }
FORCE_INLINE float rawBedTemp() { return current_temperature_bed_raw; }
FORCE_INLINE float rawChamberTemp() { return current_temperature_chamber_raw; }
FORCE_INLINE float rawCoolerTemp() { return current_temperature_cooler_raw; }
#endif
FORCE_INLINE float degTargetHotend(uint8_t hotend) { return target_temperature[HOTEND_ARG]; }
FORCE_INLINE float degTargetBed() { return target_temperature_bed; }
FORCE_INLINE float degTargetChamber() { return target_temperature_chamber; }
FORCE_INLINE float degTargetCooler() { return target_temperature_cooler; }
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
void start_watching_heater(int h = 0);
#endif
#if ENABLED(THERMAL_PROTECTION_COOLERS)
void start_watching_cooler();
#endif
#if ENABLED(THERMAL_PROTECTION_BED)
void start_watching_bed();
#endif
#if ENABLED(THERMAL_PROTECTION_CHAMBER)
void start_watching_chamber();
#endif
#if ENABLED(THERMAL_PROTECTION_COOLER)
void start_watching_cooler();
#endif
FORCE_INLINE void setTargetHotend(const float& celsius, uint8_t hotend) {
target_temperature[HOTEND_ARG] = celsius;
#if ENABLED(THERMAL_PROTECTION_HOTENDS)
......@@ -159,20 +175,28 @@ FORCE_INLINE void setTargetBed(const float& celsius) {
#endif
}
FORCE_INLINE void setTargetChamber(const float& celsius) {
target_temperature_chamber = celsius;
#if ENABLED(THERMAL_PROTECTION_CHAMBER)
start_watching_chamber();
#endif
}
FORCE_INLINE void setTargetCooler(const float& celsius) {
target_temperature_cooler = celsius;
#if ENABLED(THERMAL_PROTECTION_COOLER) && ENABLED(THERMAL_PROTECTION_COOLER_WATCHDOG)
#if ENABLED(THERMAL_PROTECTION_COOLER)
start_watching_cooler();
#endif
}
FORCE_INLINE bool isHeatingHotend(uint8_t hotend) { return target_temperature[HOTEND_ARG] > current_temperature[HOTEND_ARG]; }
FORCE_INLINE bool isHeatingBed() { return target_temperature_bed > current_temperature_bed; }
FORCE_INLINE bool isHeatingChamber() { return target_temperature_chamber > current_temperature_chamber; }
FORCE_INLINE bool isHeatingCooler() { return target_temperature_cooler > current_temperature_cooler; }
FORCE_INLINE bool isCoolingHotend(uint8_t hotend) { return target_temperature[HOTEND_ARG] < current_temperature[HOTEND_ARG]; }
FORCE_INLINE bool isCoolingBed() { return target_temperature_bed < current_temperature_bed; }
FORCE_INLINE bool isCoolingChamber() { return target_temperature_chamber < current_temperature_chamber; }
FORCE_INLINE bool isCoolingCooler() { return target_temperature_cooler < current_temperature_cooler; }
#define HOTEND_ROUTINES(NR) \
......@@ -199,6 +223,8 @@ HOTEND_ROUTINES(0);
#endif
int getHeaterPower(int heater);
int getBedPower();
int getChamberPower();
int getCoolerPower();
unsigned char getPwmCooler(bool soft);
......
......@@ -25,7 +25,7 @@
#define OVERSAMPLENR 16
#if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1) || (THERMISTORHEATER_2 == 1) || (THERMISTORHEATER_3 == 1) || (THERMISTORBED == 1) || (THERMISTORCOOLER == 1) //100k bed thermistor
#if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1) || (THERMISTORHEATER_2 == 1) || (THERMISTORHEATER_3 == 1) || (THERMISTORBED == 1) || (THERMISTORCHAMBER == 1) || (THERMISTORCOOLER == 1) //100k bed thermistor
const short temptable_1[][2] PROGMEM = {
{23 * OVERSAMPLENR, 300},
{25 * OVERSAMPLENR, 295},
......@@ -91,7 +91,7 @@ const short temptable_1[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORHEATER_3 == 2) || (THERMISTORBED == 2) || (THERMISTORCOOLER == 2) //200k bed thermistor
#if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORHEATER_3 == 2) || (THERMISTORBED == 2) || (THERMISTORCHAMBER == 2) || (THERMISTORCOOLER == 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
......@@ -132,7 +132,7 @@ const short temptable_2[][2] PROGMEM = {
#endif
#if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORHEATER_3 == 3) || (THERMISTORBED == 3) || (THERMISTORCOOLER == 3)//mendel-parts
#if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORHEATER_3 == 3) || (THERMISTORBED == 3) || (THERMISTORCHAMBER == 3) || (THERMISTORCOOLER == 3)//mendel-parts
const short temptable_3[][2] PROGMEM = {
{1 * OVERSAMPLENR, 864},
{21 * OVERSAMPLENR, 300},
......@@ -165,7 +165,7 @@ const short temptable_3[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORHEATER_3 == 4) || (THERMISTORBED == 4) || (THERMISTORCOOLER == 4) //10k thermistor
#if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORHEATER_3 == 4) || (THERMISTORBED == 4) || (THERMISTORCHAMBER == 4) || (THERMISTORCOOLER == 4) //10k thermistor
const short temptable_4[][2] PROGMEM = {
{1 * OVERSAMPLENR, 430},
{54 * OVERSAMPLENR, 137},
......@@ -190,7 +190,7 @@ const short temptable_4[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORHEATER_2 == 5) || (THERMISTORHEATER_3 == 5) || (THERMISTORBED == 5) || (THERMISTORCOOLER == 5)//100k ParCan thermistor (104GT-2)
#if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORHEATER_2 == 5) || (THERMISTORHEATER_3 == 5) || (THERMISTORBED == 5) || (THERMISTORCHAMBER == 5) || (THERMISTORCOOLER == 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
......@@ -230,7 +230,7 @@ const short temptable_5[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORHEATER_2 == 6) || (THERMISTORHEATER_3 == 6) || (THERMISTORBED == 6) || (THERMISTORCOOLER == 6)// 100k Epcos thermistor
#if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORHEATER_2 == 6) || (THERMISTORHEATER_3 == 6) || (THERMISTORBED == 6) || (THERMISTORCHAMBER == 6) || (THERMISTORCOOLER == 6)// 100k Epcos thermistor
const short temptable_6[][2] PROGMEM = {
{1 * OVERSAMPLENR, 350},
{28 * OVERSAMPLENR, 250}, //top rating 250C
......@@ -273,7 +273,7 @@ const short temptable_6[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORHEATER_2 == 7) || (THERMISTORHEATER_3 == 7) || (THERMISTORBED == 7) || (THERMISTORCOOLER == 7)// 100k Honeywell 135-104LAG-J01
#if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORHEATER_2 == 7) || (THERMISTORHEATER_3 == 7) || (THERMISTORBED == 7) || (THERMISTORCHAMBER == 7) || (THERMISTORCOOLER == 7)// 100k Honeywell 135-104LAG-J01
const short temptable_7[][2] PROGMEM = {
{1 * OVERSAMPLENR, 941},
{19 * OVERSAMPLENR, 362},
......@@ -336,7 +336,7 @@ const short temptable_7[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 71) || (THERMISTORHEATER_1 == 71) || (THERMISTORHEATER_2 == 71) || (THERMISTORHEATER_3 == 71) || (THERMISTORBED == 71) || (THERMISTORCOOLER == 71)// 100k Honeywell 135-104LAF-J01
#if (THERMISTORHEATER_0 == 71) || (THERMISTORHEATER_1 == 71) || (THERMISTORHEATER_2 == 71) || (THERMISTORHEATER_3 == 71) || (THERMISTORBED == 71) || (THERMISTORCHAMBER == 71) || (THERMISTORCOOLER == 71)// 100k Honeywell 135-104LAF-J01
// R0 = 100000 Ohm
// T0 = 25 °C
// Beta = 3974
......@@ -487,7 +487,7 @@ const short temptable_71[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 8) || (THERMISTORHEATER_1 == 8) || (THERMISTORHEATER_2 == 8) || (THERMISTORHEATER_3 == 8) || (THERMISTORBED == 8) || (THERMISTORCOOLER == 8)
#if (THERMISTORHEATER_0 == 8) || (THERMISTORHEATER_1 == 8) || (THERMISTORHEATER_2 == 8) || (THERMISTORHEATER_3 == 8) || (THERMISTORBED == 8) || (THERMISTORCHAMBER == 8) || (THERMISTORCOOLER == 8)
// 100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup)
const short temptable_8[][2] PROGMEM = {
{1 * OVERSAMPLENR, 704},
......@@ -513,7 +513,7 @@ const short temptable_8[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 9) || (THERMISTORHEATER_1 == 9) || (THERMISTORHEATER_2 == 9) || (THERMISTORHEATER_3 == 9) || (THERMISTORBED == 9) || (THERMISTORCOOLER == 9)
#if (THERMISTORHEATER_0 == 9) || (THERMISTORHEATER_1 == 9) || (THERMISTORHEATER_2 == 9) || (THERMISTORHEATER_3 == 9) || (THERMISTORBED == 9) || (THERMISTORCHAMBER == 9) || (THERMISTORCOOLER == 9)
// 100k GE Sensing AL03006-58.2K-97-G1 (4.7k pullup)
const short temptable_9[][2] PROGMEM = {
{1 * OVERSAMPLENR, 936},
......@@ -550,7 +550,7 @@ const short temptable_9[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 10) || (THERMISTORHEATER_1 == 10) || (THERMISTORHEATER_2 == 10) || (THERMISTORHEATER_3 == 10) || (THERMISTORBED == 10) || (THERMISTORCOOLER == 10)
#if (THERMISTORHEATER_0 == 10) || (THERMISTORHEATER_1 == 10) || (THERMISTORHEATER_2 == 10) || (THERMISTORHEATER_3 == 10) || (THERMISTORBED == 10) || (THERMISTORCHAMBER == 10) || (THERMISTORCOOLER == 10)
// 100k RS thermistor 198-961 (4.7k pullup)
const short temptable_10[][2] PROGMEM = {
{1 * OVERSAMPLENR, 929},
......@@ -587,7 +587,7 @@ const short temptable_10[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 11) || (THERMISTORHEATER_1 == 11) || (THERMISTORHEATER_2 == 11) || (THERMISTORHEATER_3 == 11) || (THERMISTORBED == 11) || (THERMISTORCOOLER == 11)
#if (THERMISTORHEATER_0 == 11) || (THERMISTORHEATER_1 == 11) || (THERMISTORHEATER_2 == 11) || (THERMISTORHEATER_3 == 11) || (THERMISTORBED == 11) || (THERMISTORCHAMBER == 11) || (THERMISTORCOOLER == 11)
// QU-BD silicone bed QWG-104F-3950 thermistor
const short temptable_11[][2] PROGMEM = {
{1 * OVERSAMPLENR, 938},
......@@ -643,7 +643,7 @@ const short temptable_11[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 13) || (THERMISTORHEATER_1 == 13) || (THERMISTORHEATER_2 == 13) || (THERMISTORHEATER_3 == 13) || (THERMISTORBED == 13) || (THERMISTORCOOLER == 13)
#if (THERMISTORHEATER_0 == 13) || (THERMISTORHEATER_1 == 13) || (THERMISTORHEATER_2 == 13) || (THERMISTORHEATER_3 == 13) || (THERMISTORBED == 13) || (THERMISTORCHAMBER == 13) || (THERMISTORCOOLER == 13)
// Hisens thermistor B25/50 =3950 +/-1%
const short temptable_13[][2] PROGMEM = {
{ 20.04 * OVERSAMPLENR, 300 },
......@@ -673,7 +673,7 @@ const short temptable_13[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 20) || (THERMISTORHEATER_1 == 20) || (THERMISTORHEATER_2 == 20) || (THERMISTORHEATER_3 == 20) || (THERMISTORBED == 20) || (THERMISTORCOOLER == 20) // PT100 with INA826 amp on Ultimaker v2.0 electronics
#if (THERMISTORHEATER_0 == 20) || (THERMISTORHEATER_1 == 20) || (THERMISTORHEATER_2 == 20) || (THERMISTORHEATER_3 == 20) || (THERMISTORBED == 20) || (THERMISTORCHAMBER == 20) || (THERMISTORCOOLER == 20) // PT100 with INA826 amp on Ultimaker v2.0 electronics
/* The PT100 in the Ultimaker v2.0 electronics has a high sample value for a high temperature.
This does not match the normal thermistor behaviour so we need to set the following defines */
#if (THERMISTORHEATER_0 == 20)
......@@ -753,7 +753,7 @@ const short temptable_20[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 40) || (THERMISTORHEATER_1 == 40) || (THERMISTORHEATER_2 == 40) || (THERMISTORHEATER_3 == 40) || (THERMISTORBED == 40) || (THERMISTORCOOLER == 40)
#if (THERMISTORHEATER_0 == 40) || (THERMISTORHEATER_1 == 40) || (THERMISTORHEATER_2 == 40) || (THERMISTORHEATER_3 == 40) || (THERMISTORBED == 40) || (THERMISTORCHAMBER == 40) || (THERMISTORCOOLER == 40)
// 10k Carel NTC015WH01 or ELIWELL SN8T6A1502 (4.7k pullup)
// roughly calculated using datasheet ( 10k at 25 celsius ), my body temp ( 35.9 celsius, 6.66k ) and my freezer ( -21 celsius, 56k )
// Unbelivable, seems to be pretty precise.
......@@ -796,7 +796,7 @@ const short temptable_40[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 51) || (THERMISTORHEATER_1 == 51) || (THERMISTORHEATER_2 == 51) || (THERMISTORHEATER_3 == 51) || (THERMISTORBED == 51) || (THERMISTORCOOLER == 51)
#if (THERMISTORHEATER_0 == 51) || (THERMISTORHEATER_1 == 51) || (THERMISTORHEATER_2 == 51) || (THERMISTORHEATER_3 == 51) || (THERMISTORBED == 51) || (THERMISTORCHAMBER == 51) || (THERMISTORCOOLER == 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
......@@ -858,7 +858,7 @@ const short temptable_51[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 52) || (THERMISTORHEATER_1 == 52) || (THERMISTORHEATER_2 == 52) || (THERMISTORHEATER_3 == 52) || (THERMISTORBED == 52) || (THERMISTORCOOLER == 52)
#if (THERMISTORHEATER_0 == 52) || (THERMISTORHEATER_1 == 52) || (THERMISTORHEATER_2 == 52) || (THERMISTORHEATER_3 == 52) || (THERMISTORBED == 52) || (THERMISTORCHAMBER == 52) || (THERMISTORCOOLER == 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
......@@ -899,7 +899,7 @@ const short temptable_52[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 55) || (THERMISTORHEATER_1 == 55) || (THERMISTORHEATER_2 == 55) || (THERMISTORHEATER_3 == 55) || (THERMISTORBED == 55) || (THERMISTORCOOLER == 55)
#if (THERMISTORHEATER_0 == 55) || (THERMISTORHEATER_1 == 55) || (THERMISTORHEATER_2 == 55) || (THERMISTORHEATER_3 == 55) || (THERMISTORBED == 55) || (THERMISTORCHAMBER == 55) || (THERMISTORCOOLER == 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
......@@ -940,7 +940,7 @@ const short temptable_55[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 60) || (THERMISTORHEATER_1 == 60) || (THERMISTORHEATER_2 == 60) || (THERMISTORHEATER_3 == 60) || (THERMISTORBED == 60) || (THERMISTORCOOLER == 60) // Maker's Tool Works Kapton Bed Thermister
#if (THERMISTORHEATER_0 == 60) || (THERMISTORHEATER_1 == 60) || (THERMISTORHEATER_2 == 60) || (THERMISTORHEATER_3 == 60) || (THERMISTORBED == 60) || (THERMISTORCHAMBER == 60) || (THERMISTORCOOLER == 60) // Maker's Tool Works Kapton Bed Thermister
// ./createTemperatureLookup.py --r0=100000 --t0=25 --r1=0 --r2=4700 --beta=3950
// r0: 100000
// t0: 25
......@@ -1025,7 +1025,7 @@ const short temptable_60[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 12) || (THERMISTORHEATER_1 == 12) || (THERMISTORHEATER_2 == 12) || (THERMISTORHEATER_3 == 12) || (THERMISTORBED == 12) || (THERMISTORCOOLER == 12)
#if (THERMISTORHEATER_0 == 12) || (THERMISTORHEATER_1 == 12) || (THERMISTORHEATER_2 == 12) || (THERMISTORHEATER_3 == 12) || (THERMISTORBED == 12) || (THERMISTORCHAMBER == 12) || (THERMISTORCOOLER == 12)
//100k 0603 SMD Vishay NTCS0603E3104FXT (4.7k pullup) (calibrated for Makibox hot bed)
const short temptable_12[][2] PROGMEM = {
{35 * OVERSAMPLENR, 180}, //top rating 180C
......@@ -1072,7 +1072,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) || (THERMISTORHEATER_3 == 110) || (THERMISTORBED == 110) || (THERMISTORCOOLER == 110)// Pt100 with 1k0 pullup
#if (THERMISTORHEATER_0 == 110) || (THERMISTORHEATER_1 == 110) || (THERMISTORHEATER_2 == 110) || (THERMISTORHEATER_3 == 110) || (THERMISTORBED == 110) || (THERMISTORCHAMBER == 110) || (THERMISTORCOOLER == 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)
......@@ -1085,7 +1085,7 @@ const short temptable_110[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 147) || (THERMISTORHEATER_1 == 147) || (THERMISTORHEATER_2 == 147) || (THERMISTORHEATER_3 == 147) || (THERMISTORBED == 147) || (THERMISTORCOOLER == 147) // Pt100 with 4k7 pullup
#if (THERMISTORHEATER_0 == 147) || (THERMISTORHEATER_1 == 147) || (THERMISTORHEATER_2 == 147) || (THERMISTORHEATER_3 == 147) || (THERMISTORBED == 147) || (THERMISTORCHAMBER == 147) || (THERMISTORCOOLER == 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)
......@@ -1098,7 +1098,7 @@ const short temptable_147[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 1010) || (THERMISTORHEATER_1 == 1010) || (THERMISTORHEATER_2 == 1010) || (THERMISTORHEATER_3 == 1010) || (THERMISTORBED == 1010) || (THERMISTORCOOLER == 1010) // Pt1000 with 1k0 pullup
#if (THERMISTORHEATER_0 == 1010) || (THERMISTORHEATER_1 == 1010) || (THERMISTORHEATER_2 == 1010) || (THERMISTORHEATER_3 == 1010) || (THERMISTORBED == 1010) || (THERMISTORCHAMBER == 1010) || (THERMISTORCOOLER == 1010) // Pt1000 with 1k0 pullup
const short temptable_1010[][2] PROGMEM = {
PtLine(0, 1000, 1000)
PtLine(25, 1000, 1000)
......@@ -1116,7 +1116,7 @@ const short temptable_1010[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 1047) || (THERMISTORHEATER_1 == 1047) || (THERMISTORHEATER_2 == 1047) || (THERMISTORHEATER_3 == 1047) || (THERMISTORBED == 1047) || (THERMISTORCOOLER == 1047) // Pt1000 with 4k7 pullup
#if (THERMISTORHEATER_0 == 1047) || (THERMISTORHEATER_1 == 1047) || (THERMISTORHEATER_2 == 1047) || (THERMISTORHEATER_3 == 1047) || (THERMISTORBED == 1047) || (THERMISTORCHAMBER == 1047) || (THERMISTORCOOLER == 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)
......@@ -1129,7 +1129,7 @@ const short temptable_1047[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 999) || (THERMISTORHEATER_1 == 999) || (THERMISTORHEATER_2 == 999) || (THERMISTORHEATER_3 == 999) || (THERMISTORBED == 999) || (THERMISTORCOOLER == 999)//User defined table
#if (THERMISTORHEATER_0 == 999) || (THERMISTORHEATER_1 == 999) || (THERMISTORHEATER_2 == 999) || (THERMISTORHEATER_3 == 999) || (THERMISTORBED == 999) || (THERMISTORCHAMBER == 999) || (THERMISTORCOOLER == 999)//User defined table
// Dummy Thermistor table.. It will ALWAYS read a fixed value.
#ifndef DUMMY_THERMISTOR_999_VALUE
#define DUMMY_THERMISTOR_999_VALUE 25
......@@ -1140,7 +1140,7 @@ const short temptable_1047[][2] PROGMEM = {
};
#endif
#if (THERMISTORHEATER_0 == 998) || (THERMISTORHEATER_1 == 998) || (THERMISTORHEATER_2 == 998) || (THERMISTORHEATER_3 == 998) || (THERMISTORBED == 998) || (THERMISTORCOOLER == 998)//User defined table
#if (THERMISTORHEATER_0 == 998) || (THERMISTORHEATER_1 == 998) || (THERMISTORHEATER_2 == 998) || (THERMISTORHEATER_3 == 998) || (THERMISTORBED == 998) || (THERMISTORCHAMBER == 998) || (THERMISTORCOOLER == 998)//User defined table
// Dummy Thermistor table.. It will ALWAYS read a fixed value.
#ifndef DUMMY_THERMISTOR_998_VALUE
#define DUMMY_THERMISTOR_998_VALUE 25
......@@ -1256,16 +1256,6 @@ const short temptable_1047[][2] PROGMEM = {
#endif // BED_USES_THERMISTOR
#endif
#ifdef THERMISTORCOOLER
#define COOLERTEMPTABLE TT_NAME(THERMISTORCOOLER)
#define COOLERTEMPTABLE_LEN COUNT(COOLERTEMPTABLE)
#else
#ifdef COOLER_USES_THERMISTOR
#error No Cooler thermistor table specified
#endif // COOLER_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_BED_RAW_HI_TEMP
#ifdef BED_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
......@@ -1277,6 +1267,34 @@ const short temptable_1047[][2] PROGMEM = {
#endif
#endif
#ifdef THERMISTORCHAMBER
#define CHAMBERTEMPTABLE TT_NAME(THERMISTORCHAMBER)
#define CHAMBERTEMPTABLE_LEN COUNT(CHAMBERTEMPTABLE)
#else
#ifdef CHAMBER_USES_THERMISTOR
#error No chamber thermistor table specified
#endif // CHAMBER_USES_THERMISTOR
#endif
#ifndef HEATER_CHAMBER_RAW_HI_TEMP
#ifdef CHAMBER_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
#define HEATER_CHAMBER_RAW_HI_TEMP 0
#define HEATER_CHAMBER_RAW_LO_TEMP 16383
#else //In case of an thermocouple the highest temperature results in the highest ADC value
#define HEATER_CHAMBER_RAW_HI_TEMP 16383
#define HEATER_CHAMBER_RAW_LO_TEMP 0
#endif
#endif
#ifdef THERMISTORCOOLER
#define COOLERTEMPTABLE TT_NAME(THERMISTORCOOLER)
#define COOLERTEMPTABLE_LEN COUNT(COOLERTEMPTABLE)
#else
#ifdef COOLER_USES_THERMISTOR
#error No Cooler thermistor table specified
#endif // COOLER_USES_THERMISTOR
#endif
#ifndef COOLER_RAW_HI_TEMP
#ifdef COOLER_USES_THERMISTOR //In case of a thermistor the highest temperature results in the lowest ADC value
#define COOLER_RAW_HI_TEMP 0
......@@ -1287,5 +1305,4 @@ const short temptable_1047[][2] PROGMEM = {
#endif
#endif
#endif //THERMISTORTABLES_H_
#endif // THERMISTORTABLES_H_
......@@ -54,6 +54,8 @@ Added total filament printed writed in SD CARD.
Added anti extruder idle oozing system.
Added Hysteresis and Z-Wobble correction (only cartesian printers).
Added support reader TAG width MFRC522
Added Cooler and Hot Chamber
Added Laser beam and raster base64
## Credits
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment