Implement automatic extruder/cold-end fan control based on temperature
This change allows fan outputs to automatically turn on/off when the associated nozzle temperature of an extruder is above/below a threshold temperature. Multiple extruders can be assigned to the same pin in which case the fan will turn on when any selected extruder is above the threshold. It also makes the M42 command compatible with the M106/M107 command. The majority of the logic in this change will be evaluated by the compiler at build time (i.e, low code space requirements).
This commit is contained in:
parent
4eb81a69e6
commit
372e12f83f
4 changed files with 302 additions and 234 deletions
|
@ -71,6 +71,16 @@
|
|||
// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
|
||||
//#define FAN_KICKSTART_TIME 100
|
||||
|
||||
// Configure fan pin outputs to automatically turn on/off when the associated
|
||||
// extruder temperature is above/below EXTRUDER_AUTO_FAN_TEMPERATURE.
|
||||
// Multiple extruders can be assigned to the same pin in which case
|
||||
// the fan will turn on when any selected extruder is above the threshold.
|
||||
#define EXTRUDER_0_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_1_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_2_AUTO_FAN_PIN -1
|
||||
#define EXTRUDER_AUTO_FAN_TEMPERATURE 50
|
||||
#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed
|
||||
|
||||
//===========================================================================
|
||||
//=============================Mechanical Settings===========================
|
||||
//===========================================================================
|
||||
|
|
|
@ -982,6 +982,10 @@ void process_commands()
|
|||
break;
|
||||
}
|
||||
}
|
||||
#if FAN_PIN > -1
|
||||
if (pin_number == FAN_PIN)
|
||||
fanSpeed = pin_status;
|
||||
#endif
|
||||
if (pin_number > -1)
|
||||
{
|
||||
pinMode(pin_number, OUTPUT);
|
||||
|
|
|
@ -99,8 +99,9 @@ static volatile bool temp_meas_ready = false;
|
|||
#ifdef FAN_SOFT_PWM
|
||||
static unsigned char soft_pwm_fan;
|
||||
#endif
|
||||
|
||||
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN > -1 || EXTRUDER_1_AUTO_FAN_PIN > -1 || EXTRUDER_2_AUTO_FAN_PIN > -1
|
||||
static uint8_t extruderAutoFanState = 0; // extruder auto fan state stored as bitmap
|
||||
#endif
|
||||
|
||||
#if EXTRUDERS > 3
|
||||
# error Unsupported number of extruders
|
||||
|
@ -399,6 +400,55 @@ void manage_heater()
|
|||
|
||||
} // End extruder for loop
|
||||
|
||||
#if EXTRUDER_0_AUTO_FAN_PIN > -1
|
||||
// check the extruder 0 setting (and any ganged auto fan outputs)
|
||||
bool newFanState = (EXTRUDER_0_AUTO_FAN_PIN > -1 &&
|
||||
(current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE ||
|
||||
(EXTRUDER_0_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN && current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) ||
|
||||
(EXTRUDER_0_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN && current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE)));
|
||||
if ((extruderAutoFanState & 1) != newFanState) // store state in first bit
|
||||
{
|
||||
int newFanSpeed = (newFanState ? EXTRUDER_AUTO_FAN_SPEED : 0);
|
||||
if (EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN)
|
||||
fanSpeed = newFanSpeed;
|
||||
pinMode(EXTRUDER_0_AUTO_FAN_PIN, OUTPUT);
|
||||
digitalWrite(EXTRUDER_0_AUTO_FAN_PIN, newFanSpeed);
|
||||
analogWrite(EXTRUDER_0_AUTO_FAN_PIN, newFanSpeed);
|
||||
extruderAutoFanState = newFanState | (extruderAutoFanState & ~1);
|
||||
}
|
||||
#endif //EXTRUDER_0_AUTO_FAN_PIN > -1
|
||||
#if EXTRUDER_1_AUTO_FAN_PIN > -1
|
||||
// check the extruder 1 setting (except when extruder 1 is the same as 0)
|
||||
newFanState = (EXTRUDER_1_AUTO_FAN_PIN > -1 && EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN &&
|
||||
(current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE ||
|
||||
(EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN && current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE)));
|
||||
if ((extruderAutoFanState & 2) != (newFanState<<1)) // use second bit
|
||||
{
|
||||
int newFanSpeed = (newFanState ? EXTRUDER_AUTO_FAN_SPEED : 0);
|
||||
if (EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN)
|
||||
fanSpeed = newFanSpeed;
|
||||
pinMode(EXTRUDER_1_AUTO_FAN_PIN, OUTPUT);
|
||||
digitalWrite(EXTRUDER_1_AUTO_FAN_PIN, newFanSpeed);
|
||||
analogWrite(EXTRUDER_1_AUTO_FAN_PIN, newFanSpeed);
|
||||
extruderAutoFanState = (newFanState<<1) | (extruderAutoFanState & ~2);
|
||||
}
|
||||
#endif //EXTRUDER_1_AUTO_FAN_PIN > -1
|
||||
#if EXTRUDER_2_AUTO_FAN_PIN > -1
|
||||
// check the extruder 2 setting (except when extruder 2 is the same as 1 or 0)
|
||||
newFanState = (EXTRUDER_2_AUTO_FAN_PIN > -1 &&
|
||||
EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN &&
|
||||
current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE);
|
||||
if ((extruderAutoFanState & 4) != (newFanState<<2)) // use third bit
|
||||
{
|
||||
int newFanSpeed = (newFanState ? EXTRUDER_AUTO_FAN_SPEED : 0);
|
||||
if (EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN)
|
||||
fanSpeed = newFanSpeed;
|
||||
pinMode(EXTRUDER_2_AUTO_FAN_PIN, OUTPUT);
|
||||
digitalWrite(EXTRUDER_2_AUTO_FAN_PIN, newFanSpeed);
|
||||
analogWrite(EXTRUDER_2_AUTO_FAN_PIN, newFanSpeed);
|
||||
extruderAutoFanState = (newFanState<<2) | (extruderAutoFanState & ~4);
|
||||
}
|
||||
#endif //EXTRUDER_2_AUTO_FAN_PIN > -1
|
||||
|
||||
#ifndef PIDTEMPBED
|
||||
if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
|
||||
|
|
16
README.md
16
README.md
|
@ -1,10 +1,13 @@
|
|||
WARNING:
|
||||
--------
|
||||
THIS IS RELEASE CANDIDATE 2 FOR MARLIN 1.0.0
|
||||
==========================
|
||||
Marlin 3D Printer Firmware
|
||||
==========================
|
||||
|
||||
The configuration is now split in two files
|
||||
Configuration.h for the normal settings
|
||||
Configuration_adv.h for the advanced settings
|
||||
Notes:
|
||||
-----
|
||||
|
||||
The configuration is now split in two files:
|
||||
Configuration.h for the normal settings
|
||||
Configuration_adv.h for the advanced settings
|
||||
|
||||
Gen7T is not supported.
|
||||
|
||||
|
@ -46,6 +49,7 @@ Features:
|
|||
* PID tuning
|
||||
* CoreXY kinematics (www.corexy.com/theory.html)
|
||||
* Configurable serial port to support connection of wireless adaptors.
|
||||
* Automatic operation of extruder/cold-end cooling fans based on nozzle temperature
|
||||
|
||||
The default baudrate is 250000. This baudrate has less jitter and hence errors than the usual 115200 baud, but is less supported by drivers and host-environments.
|
||||
|
||||
|
|
Reference in a new issue