Browse Source

Allow increasing the software PWM frequency.

pull/1/head
Erik van der Zalm 12 years ago
parent
commit
c8dcc7c208
  1. 11
      Marlin/Configuration.h
  2. 4
      Marlin/Marlin.h
  3. 36
      Marlin/planner.cpp
  4. 17
      Marlin/temperature.cpp

11
Marlin/Configuration.h

@ -457,6 +457,17 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
// Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino // Increase the FAN pwm frequency. Removes the PWM noise but increases heating in the FET/Arduino
//#define FAST_PWM_FAN //#define FAST_PWM_FAN
// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency
// which is not ass annoying as with the hardware PWM. On the other hand, if this frequency
// is too low, you should also increment SOFT_PWM_SCALE.
//#define FAN_SOFT_PWM
// Incrementing this by 1 will double the software PWM frequency,
// affecting heaters, and the fan if FAN_SOFT_PWM is enabled.
// However, control resolution will be halved for each increment;
// at zero value, there are 128 effective control positions.
#define SOFT_PWM_SCALE 0
// M240 Triggers a camera by emulating a Canon RC-1 Remote // M240 Triggers a camera by emulating a Canon RC-1 Remote
// Data from: http://www.doc-diy.net/photo/rc-1_hacked/ // Data from: http://www.doc-diy.net/photo/rc-1_hacked/
// #define PHOTOGRAPH_PIN 23 // #define PHOTOGRAPH_PIN 23

4
Marlin/Marlin.h

@ -191,6 +191,10 @@ extern int ValvePressure;
extern int EtoPPressure; extern int EtoPPressure;
#endif #endif
#ifdef FAN_SOFT_PWM
extern unsigned char fanSpeedSoftPwm;
#endif
#ifdef FWRETRACT #ifdef FWRETRACT
extern bool autoretract_enabled; extern bool autoretract_enabled;
extern bool retracted; extern bool retracted;

36
Marlin/planner.cpp

@ -473,22 +473,24 @@ void check_axes_activity()
disable_e2(); disable_e2();
} }
#if defined(FAN_PIN) && FAN_PIN > -1 #if defined(FAN_PIN) && FAN_PIN > -1
#ifndef FAN_SOFT_PWM #ifdef FAN_KICKSTART_TIME
#ifdef FAN_KICKSTART_TIME static unsigned long fan_kick_end;
static unsigned long fan_kick_end; if (tail_fan_speed) {
if (tail_fan_speed) { if (fan_kick_end == 0) {
if (fan_kick_end == 0) { // Just starting up fan - run at full power.
// Just starting up fan - run at full power. fan_kick_end = millis() + FAN_KICKSTART_TIME;
fan_kick_end = millis() + FAN_KICKSTART_TIME; tail_fan_speed = 255;
tail_fan_speed = 255; } else if (fan_kick_end > millis())
} else if (fan_kick_end > millis()) // Fan still spinning up.
// Fan still spinning up. tail_fan_speed = 255;
tail_fan_speed = 255; } else {
} else { fan_kick_end = 0;
fan_kick_end = 0; }
} #endif//FAN_KICKSTART_TIME
#endif//FAN_KICKSTART_TIME #ifdef FAN_SOFT_PWM
analogWrite(FAN_PIN,tail_fan_speed); fanSpeedSoftPwm = tail_fan_speed;
#else
analogWrite(FAN_PIN,tail_fan_speed);
#endif//!FAN_SOFT_PWM #endif//!FAN_SOFT_PWM
#endif//FAN_PIN > -1 #endif//FAN_PIN > -1
#ifdef AUTOTEMP #ifdef AUTOTEMP
@ -757,7 +759,7 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS]; block->acceleration_st = axis_steps_per_sqr_second[Z_AXIS];
} }
block->acceleration = block->acceleration_st / steps_per_mm; block->acceleration = block->acceleration_st / steps_per_mm;
block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608); block->acceleration_rate = (long)((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));
#if 0 // Use old jerk for now #if 0 // Use old jerk for now
// Compute path unit vector // Compute path unit vector

17
Marlin/temperature.cpp

@ -62,6 +62,9 @@ float current_temperature_bed = 0.0;
float bedKd=(DEFAULT_bedKd/PID_dT); float bedKd=(DEFAULT_bedKd/PID_dT);
#endif //PIDTEMPBED #endif //PIDTEMPBED
#ifdef FAN_SOFT_PWM
unsigned char fanSpeedSoftPwm;
#endif
//=========================================================================== //===========================================================================
//=============================private variables============================ //=============================private variables============================
@ -145,6 +148,10 @@ int watch_start_temp[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0); unsigned long watchmillis[EXTRUDERS] = ARRAY_BY_EXTRUDERS(0,0,0);
#endif //WATCH_TEMP_PERIOD #endif //WATCH_TEMP_PERIOD
#ifndef SOFT_PWM_SCALE
#define SOFT_PWM_SCALE 0
#endif
//=========================================================================== //===========================================================================
//============================= functions ============================ //============================= functions ============================
//=========================================================================== //===========================================================================
@ -720,8 +727,8 @@ void tp_init()
setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8 setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
#endif #endif
#ifdef FAN_SOFT_PWM #ifdef FAN_SOFT_PWM
soft_pwm_fan=(unsigned char)fanSpeed; soft_pwm_fan = fanSpeedSoftPwm / 2;
#endif #endif
#endif #endif
#ifdef HEATER_0_USES_MAX6675 #ifdef HEATER_0_USES_MAX6675
@ -1028,7 +1035,7 @@ ISR(TIMER0_COMPB_vect)
static unsigned long raw_temp_2_value = 0; static unsigned long raw_temp_2_value = 0;
static unsigned long raw_temp_bed_value = 0; static unsigned long raw_temp_bed_value = 0;
static unsigned char temp_state = 0; static unsigned char temp_state = 0;
static unsigned char pwm_count = 1; static unsigned char pwm_count = (1 << SOFT_PWM_SCALE);
static unsigned char soft_pwm_0; static unsigned char soft_pwm_0;
#if EXTRUDERS > 1 #if EXTRUDERS > 1
static unsigned char soft_pwm_1; static unsigned char soft_pwm_1;
@ -1056,7 +1063,7 @@ ISR(TIMER0_COMPB_vect)
if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1); if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
#endif #endif
#ifdef FAN_SOFT_PWM #ifdef FAN_SOFT_PWM
soft_pwm_fan =(unsigned char) fanSpeed; soft_pwm_fan = fanSpeedSoftPwm / 2;
if(soft_pwm_fan > 0) WRITE(FAN_PIN,1); if(soft_pwm_fan > 0) WRITE(FAN_PIN,1);
#endif #endif
} }
@ -1074,7 +1081,7 @@ ISR(TIMER0_COMPB_vect)
if(soft_pwm_fan <= pwm_count) WRITE(FAN_PIN,0); if(soft_pwm_fan <= pwm_count) WRITE(FAN_PIN,0);
#endif #endif
pwm_count++; pwm_count += (1 << SOFT_PWM_SCALE);
pwm_count &= 0x7f; pwm_count &= 0x7f;
switch(temp_state) { switch(temp_state) {

Loading…
Cancel
Save