From d5ad7a0814aff16b371fbe2c75ff54d66fd9572d Mon Sep 17 00:00:00 2001 From: Robert F-C Date: Tue, 30 Apr 2013 01:08:29 +1000 Subject: [PATCH] Rework change to incorporate CONTROLLERFAN Also refactor extruder auto fan logic to simplify further and now only check every 2.5 seconds --- Marlin/Configuration_adv.h | 7 +- Marlin/Marlin_main.cpp | 49 +++++--------- Marlin/temperature.cpp | 128 ++++++++++++++++++++++--------------- 3 files changed, 98 insertions(+), 86 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6d164c4f5c..afdd684415 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -63,14 +63,16 @@ //This is for controlling a fan to cool down the stepper drivers //it will turn on when any driver is enabled //and turn off after the set amount of seconds from last driver being disabled again -//#define CONTROLLERFAN_PIN 23 //Pin used for the fan to cool controller, comment out to disable this function -#define CONTROLLERFAN_SEC 60 //How many seconds, after all motors were disabled, the fan should run +#define CONTROLLERFAN_PIN -1 //Pin used for the fan to cool controller (-1 to disable) +#define CONTROLLERFAN_SECS 60 //How many seconds, after all motors were disabled, the fan should run +#define CONTROLLERFAN_SPEED 255 // == full speed // When first starting the main fan, run it at full speed for the // given number of milliseconds. This gets the fan spinning reliably // before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu) //#define FAN_KICKSTART_TIME 100 +// Extruder cooling fans // 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 @@ -81,6 +83,7 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed + //=========================================================================== //=============================Mechanical Settings=========================== //=========================================================================== diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 69f464b296..a3eac5d2ce 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -374,13 +374,9 @@ void setup() lcd_init(); - #ifdef CONTROLLERFAN_PIN + #if CONTROLLERFAN_PIN > 0 SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan - #endif - - #ifdef EXTRUDERFAN_PIN - SET_OUTPUT(EXTRUDERFAN_PIN); //Set pin used for extruder cooling fan - #endif + #endif } @@ -1963,7 +1959,12 @@ void prepare_arc_move(char isclockwise) { previous_millis_cmd = millis(); } -#ifdef CONTROLLERFAN_PIN +#if CONTROLLERFAN_PIN > 0 + +#if CONTROLLERFAN_PIN == FAN_PIN + #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN" +#endif + unsigned long lastMotor = 0; //Save the time for when a motor was turned on last unsigned long lastMotorCheck = 0; @@ -1985,34 +1986,16 @@ void controllerFan() lastMotor = millis(); //... set time to NOW so the fan will turn on } - if ((millis() - lastMotor) >= (CONTROLLERFAN_SEC*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC... + if ((millis() - lastMotor) >= (CONTROLLERFAN_SECS*1000UL) || lastMotor == 0) //If the last time any driver was enabled, is longer since than CONTROLLERSEC... { - WRITE(CONTROLLERFAN_PIN, LOW); //... turn the fan off + digitalWrite(CONTROLLERFAN_PIN, 0); + analogWrite(CONTROLLERFAN_PIN, 0); } else { - WRITE(CONTROLLERFAN_PIN, HIGH); //... turn the fan on - } - } -} -#endif - -#ifdef EXTRUDERFAN_PIN -unsigned long lastExtruderCheck = 0; - -void extruderFan() -{ - if ((millis() - lastExtruderCheck) >= 2500) //Not a time critical function, so we only check every 2500ms - { - lastExtruderCheck = millis(); - - if (degHotend(active_extruder) < EXTRUDERFAN_DEC) - { - WRITE(EXTRUDERFAN_PIN, LOW); //... turn the fan off - } - else - { - WRITE(EXTRUDERFAN_PIN, HIGH); //... turn the fan on + // allows digital or PWM fan output to be used (see M42 handling) + digitalWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED); + analogWrite(CONTROLLERFAN_PIN, CONTROLLERFAN_SPEED); } } } @@ -2036,11 +2019,11 @@ void manage_inactivity() } } } - #if( KILL_PIN>-1 ) + #if KILL_PIN > 0 if( 0 == READ(KILL_PIN) ) kill(); #endif - #ifdef CONTROLLERFAN_PIN + #if CONTROLLERFAN_PIN > 0 controllerFan(); //Check if fan should be turned on to cool stepper drivers down #endif #ifdef EXTRUDER_RUNOUT_PREVENT diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 871bb811f2..78f1a6908f 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -99,8 +99,8 @@ 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 +#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0 + static unsigned long extruder_autofan_last_check; #endif #if EXTRUDERS > 3 @@ -307,6 +307,73 @@ int getHeaterPower(int heater) { return soft_pwm[heater]; } +#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0 + +void setExtruderAutoFanState(int pin, bool state) +{ + unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : 0; + // this idiom allows both digital and PWM fan outputs (see M42 handling). + pinMode(pin, OUTPUT); + digitalWrite(pin, newFanSpeed); + analogWrite(pin, newFanSpeed); +} + +void checkExtruderAutoFans() +{ + uint8_t fanState = 0; + + // which fan pins need to be turned on? + #if EXTRUDER_0_AUTO_FAN_PIN > 0 + #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN + #error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN" + #endif + if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE) + fanState |= 1; + #endif + #if EXTRUDER_1_AUTO_FAN_PIN > 0 + #if EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN + #error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN" + #endif + if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) + { + if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) + fanState |= 1; + else + fanState |= 2; + } + #endif + #if EXTRUDER_2_AUTO_FAN_PIN > 0 + #if EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN + #error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN" + #endif + if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE) + { + if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) + fanState |= 1; + else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN) + fanState |= 2; + else + fanState |= 4; + } + #endif + + // update extruder auto fan states + #if EXTRUDER_0_AUTO_FAN_PIN > 0 + setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0); + #endif + #if EXTRUDER_1_AUTO_FAN_PIN > 0 + if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) + setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0); + #endif + #if EXTRUDER_2_AUTO_FAN_PIN > 0 + if (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN + && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN) + setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0); + #endif +} + +#endif // any extruder auto fan pins set + void manage_heater() { float pid_input; @@ -399,56 +466,15 @@ void manage_heater() #endif } // End extruder for loop - - #if EXTRUDER_0_AUTO_FAN_PIN > -1 || EXTRUDER_1_AUTO_FAN_PIN > -1 || EXTRUDER_2_AUTO_FAN_PIN > -1 - bool newFanState; - #if EXTRUDER_0_AUTO_FAN_PIN > -1 - // check the extruder 0 setting (and any ganged auto fan outputs) - newFanState = (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 && EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN - // check the extruder 1 setting (except when extruder 1 is the same as 0) - newFanState = (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 && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN - // check the extruder 2 setting (except when extruder 2 is the same as 1 or 0) - newFanState = (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 - #endif // any AUTO_FAN_PIN enabled + #if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0 + if(millis() - extruder_autofan_last_check > 2500) // only need to check fan state very infrequently + { + checkExtruderAutoFans(); + extruder_autofan_last_check = millis(); + } + #endif + #ifndef PIDTEMPBED if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL) return;