Apply all changes from latest Marlin_V1

Diffed and merged, preserving my updates
This commit is contained in:
Scott Lahteine
2013-06-06 15:49:25 -07:00
parent a5cd582665
commit 5dabc95409
22 changed files with 3221 additions and 996 deletions

View File

@ -40,10 +40,13 @@
int target_temperature[EXTRUDERS] = { 0 };
int target_temperature_bed = 0;
int current_temperature_raw[EXTRUDERS] = { 0 };
float current_temperature[EXTRUDERS] = { 0 };
float current_temperature[EXTRUDERS] = { 0.0 };
int current_temperature_bed_raw = 0;
float current_temperature_bed = 0;
float current_temperature_bed = 0.0;
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
int redundant_temperature_raw = 0;
float redundant_temperature = 0.0;
#endif
#ifdef PIDTEMP
float Kp=DEFAULT_Kp;
float Ki=(DEFAULT_Ki*PID_dT);
@ -99,17 +102,20 @@ static volatile bool temp_meas_ready = false;
#ifdef FAN_SOFT_PWM
static unsigned char soft_pwm_fan;
#endif
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
static unsigned long extruder_autofan_last_check;
#endif
#if EXTRUDERS > 3
# error Unsupported number of extruders
# error Unsupported number of extruders
#elif EXTRUDERS > 2
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2, v3 }
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2, v3 }
#elif EXTRUDERS > 1
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2 }
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1, v2 }
#else
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1 }
# define ARRAY_BY_EXTRUDERS(v1, v2, v3) { v1 }
#endif
// Init min and max temp with extreme values to prevent false errors during startup
@ -121,8 +127,14 @@ static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 16383, 16383, 16383 );
#ifdef BED_MAXTEMP
static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
#endif
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
static void *heater_ttbl_map[2] = {(void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE };
static uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN };
#else
static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
#endif
static float analog2temp(int raw, uint8_t e);
static float analog2tempBed(int raw);
@ -154,28 +166,28 @@ void PID_autotune(float temp, int extruder, int ncycles)
float Kp, Ki, Kd;
float max = 0, min = 10000;
if ((extruder > EXTRUDERS)
if ((extruder > EXTRUDERS)
#if (TEMP_BED_PIN <= -1)
||(extruder < 0)
#endif
){
SERIAL_ECHOLN("PID Autotune failed. Bad extruder number.");
return;
}
||(extruder < 0)
#endif
){
SERIAL_ECHOLN("PID Autotune failed. Bad extruder number.");
return;
}
SERIAL_ECHOLN("PID Autotune start");
disable_heater(); // switch off all heaters.
if (extruder<0)
{
soft_pwm_bed = (MAX_BED_POWER)/2;
bias = d = (MAX_BED_POWER)/2;
}
else
{
soft_pwm[extruder] = (PID_MAX)/2;
bias = d = (PID_MAX)/2;
if (extruder<0)
{
soft_pwm_bed = (MAX_BED_POWER)/2;
bias = d = (MAX_BED_POWER)/2;
}
else
{
soft_pwm[extruder] = (PID_MAX)/2;
bias = d = (PID_MAX)/2;
}
@ -193,10 +205,10 @@ void PID_autotune(float temp, int extruder, int ncycles)
if(heating == true && input > temp) {
if(millis() - t2 > 5000) {
heating=false;
if (extruder<0)
soft_pwm_bed = (bias - d) >> 1;
else
soft_pwm[extruder] = (bias - d) >> 1;
if (extruder<0)
soft_pwm_bed = (bias - d) >> 1;
else
soft_pwm[extruder] = (bias - d) >> 1;
t1=millis();
t_high=t1 - t2;
max=temp;
@ -247,10 +259,10 @@ void PID_autotune(float temp, int extruder, int ncycles)
*/
}
}
if (extruder<0)
soft_pwm_bed = (bias + d) >> 1;
else
soft_pwm[extruder] = (bias + d) >> 1;
if (extruder<0)
soft_pwm_bed = (bias + d) >> 1;
else
soft_pwm[extruder] = (bias + d) >> 1;
cycles++;
min=temp;
}
@ -261,14 +273,14 @@ void PID_autotune(float temp, int extruder, int ncycles)
return;
}
if(millis() - temp_millis > 2000) {
int p;
if (extruder<0){
p=soft_pwm_bed;
SERIAL_PROTOCOLPGM("ok B:");
}else{
p=soft_pwm[extruder];
SERIAL_PROTOCOLPGM("ok T:");
}
int p;
if (extruder<0){
p=soft_pwm_bed;
SERIAL_PROTOCOLPGM("ok B:");
}else{
p=soft_pwm[extruder];
SERIAL_PROTOCOLPGM("ok T:");
}
SERIAL_PROTOCOL(input);
SERIAL_PROTOCOLPGM(" @:");
@ -306,6 +318,78 @@ int getHeaterPower(int heater) {
return soft_pwm[heater];
}
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
#if defined(FAN_PIN) && FAN_PIN > -1
#if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN"
#endif
#if EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN"
#endif
#if EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN
#error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN"
#endif
#endif
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 defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)
fanState |= 1;
#endif
#if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
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 defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
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 defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
#endif
#if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN)
setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0);
#endif
#if defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
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;
@ -396,10 +480,31 @@ void manage_heater()
}
}
#endif
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
if(fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) {
disable_heater();
if(IsStopped() == false) {
SERIAL_ERROR_START;
SERIAL_ERRORLNPGM("Extruder switched off. Temperature difference between temp sensors is too high !");
LCD_ALERTMESSAGEPGM("Err: REDUNDANT TEMP ERROR");
}
#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
Stop();
#endif
}
#endif
} // End extruder for loop
#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
(defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
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;
@ -481,7 +586,11 @@ void manage_heater()
// Derived from RepRap FiveD extruder::getTemperature()
// For hot end temperature measurement.
static float analog2temp(int raw, uint8_t e) {
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
if(e > EXTRUDERS)
#else
if(e >= EXTRUDERS)
#endif
{
SERIAL_ERROR_START;
SERIAL_ERROR((int)e);
@ -560,7 +669,9 @@ static void updateTemperaturesFromRawValues()
current_temperature[e] = analog2temp(current_temperature_raw[e], e);
}
current_temperature_bed = analog2tempBed(current_temperature_bed_raw);
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
redundant_temperature = analog2temp(redundant_temperature_raw, 1);
#endif
//Reset the watchdog after we know we have a temperature measurement.
watchdog_reset();
@ -571,6 +682,12 @@ static void updateTemperaturesFromRawValues()
void tp_init()
{
#if (MOTHERBOARD == 80) && ((TEMP_SENSOR_0==-1)||(TEMP_SENSOR_1==-1)||(TEMP_SENSOR_2==-1)||(TEMP_SENSOR_BED==-1))
//disable RUMBA JTAG in case the thermocouple extension is plugged on top of JTAG connector
MCUCR=(1<<JTD);
MCUCR=(1<<JTD);
#endif
// Finish init of mult extruder arrays
for(int e = 0; e < EXTRUDERS; e++) {
// populate with the first value
@ -585,19 +702,19 @@ void tp_init()
#endif //PIDTEMPBED
}
#if (HEATER_0_PIN > -1)
#if defined(HEATER_0_PIN) && (HEATER_0_PIN > -1)
SET_OUTPUT(HEATER_0_PIN);
#endif
#if (HEATER_1_PIN > -1)
#if defined(HEATER_1_PIN) && (HEATER_1_PIN > -1)
SET_OUTPUT(HEATER_1_PIN);
#endif
#if (HEATER_2_PIN > -1)
#if defined(HEATER_2_PIN) && (HEATER_2_PIN > -1)
SET_OUTPUT(HEATER_2_PIN);
#endif
#if (HEATER_BED_PIN > -1)
#if defined(HEATER_BED_PIN) && (HEATER_BED_PIN > -1)
SET_OUTPUT(HEATER_BED_PIN);
#endif
#if (FAN_PIN > -1)
#if defined(FAN_PIN) && (FAN_PIN > -1)
SET_OUTPUT(FAN_PIN);
#ifdef FAST_PWM_FAN
setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
@ -629,28 +746,28 @@ void tp_init()
#ifdef DIDR2
DIDR2 = 0;
#endif
#if (TEMP_0_PIN > -1)
#if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
#if TEMP_0_PIN < 8
DIDR0 |= 1 << TEMP_0_PIN;
#else
DIDR2 |= 1<<(TEMP_0_PIN - 8);
#endif
#endif
#if (TEMP_1_PIN > -1)
#if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
#if TEMP_1_PIN < 8
DIDR0 |= 1<<TEMP_1_PIN;
#else
DIDR2 |= 1<<(TEMP_1_PIN - 8);
#endif
#endif
#if (TEMP_2_PIN > -1)
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
#if TEMP_2_PIN < 8
DIDR0 |= 1 << TEMP_2_PIN;
#else
DIDR2 = 1<<(TEMP_2_PIN - 8);
DIDR2 |= 1<<(TEMP_2_PIN - 8);
#endif
#endif
#if (TEMP_BED_PIN > -1)
#if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
#if TEMP_BED_PIN < 8
DIDR0 |= 1<<TEMP_BED_PIN;
#else
@ -689,7 +806,7 @@ void tp_init()
#if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP)
minttemp[1] = HEATER_1_MINTEMP;
while(analog2temp(minttemp_raw[1], 1) > HEATER_1_MINTEMP) {
while(analog2temp(minttemp_raw[1], 1) < HEATER_1_MINTEMP) {
#if HEATER_1_RAW_LO_TEMP < HEATER_1_RAW_HI_TEMP
minttemp_raw[1] += OVERSAMPLENR;
#else
@ -710,7 +827,7 @@ void tp_init()
#if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP)
minttemp[2] = HEATER_2_MINTEMP;
while(analog2temp(minttemp_raw[2], 2) > HEATER_2_MINTEMP) {
while(analog2temp(minttemp_raw[2], 2) < HEATER_2_MINTEMP) {
#if HEATER_2_RAW_LO_TEMP < HEATER_2_RAW_HI_TEMP
minttemp_raw[2] += OVERSAMPLENR;
#else
@ -771,34 +888,34 @@ void disable_heater()
for(int i=0;i<EXTRUDERS;i++)
setTargetHotend(0,i);
setTargetBed(0);
#if TEMP_0_PIN > -1
#if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
target_temperature[0]=0;
soft_pwm[0]=0;
#if HEATER_0_PIN > -1
#if defined(HEATER_0_PIN) && HEATER_0_PIN > -1
WRITE(HEATER_0_PIN,LOW);
#endif
#endif
#if TEMP_1_PIN > -1
#if defined(TEMP_1_PIN) && TEMP_1_PIN > -1
target_temperature[1]=0;
soft_pwm[1]=0;
#if HEATER_1_PIN > -1
#if defined(HEATER_1_PIN) && HEATER_1_PIN > -1
WRITE(HEATER_1_PIN,LOW);
#endif
#endif
#if TEMP_2_PIN > -1
#if defined(TEMP_2_PIN) && TEMP_2_PIN > -1
target_temperature[2]=0;
soft_pwm[2]=0;
#if HEATER_2_PIN > -1
#if defined(HEATER_2_PIN) && HEATER_2_PIN > -1
WRITE(HEATER_2_PIN,LOW);
#endif
#endif
#if TEMP_BED_PIN > -1
#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
target_temperature_bed=0;
soft_pwm_bed=0;
#if HEATER_BED_PIN > -1
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
WRITE(HEATER_BED_PIN,LOW);
#endif
#endif
@ -934,7 +1051,7 @@ ISR(TIMER0_COMPB_vect)
soft_pwm_2 = soft_pwm[2];
if(soft_pwm_2 > 0) WRITE(HEATER_2_PIN,1);
#endif
#if HEATER_BED_PIN > -1
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
soft_pwm_b = soft_pwm_bed;
if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
#endif
@ -950,7 +1067,7 @@ ISR(TIMER0_COMPB_vect)
#if EXTRUDERS > 2
if(soft_pwm_2 <= pwm_count) WRITE(HEATER_2_PIN,0);
#endif
#if HEATER_BED_PIN > -1
#if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
if(soft_pwm_b <= pwm_count) WRITE(HEATER_BED_PIN,0);
#endif
#ifdef FAN_SOFT_PWM
@ -962,7 +1079,7 @@ ISR(TIMER0_COMPB_vect)
switch(temp_state) {
case 0: // Prepare TEMP_0
#if (TEMP_0_PIN > -1)
#if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
#if TEMP_0_PIN > 7
ADCSRB = 1<<MUX5;
#else
@ -975,7 +1092,7 @@ ISR(TIMER0_COMPB_vect)
temp_state = 1;
break;
case 1: // Measure TEMP_0
#if (TEMP_0_PIN > -1)
#if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
raw_temp_0_value += ADC;
#endif
#ifdef HEATER_0_USES_MAX6675 // TODO remove the blocking
@ -984,7 +1101,7 @@ ISR(TIMER0_COMPB_vect)
temp_state = 2;
break;
case 2: // Prepare TEMP_BED
#if (TEMP_BED_PIN > -1)
#if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
#if TEMP_BED_PIN > 7
ADCSRB = 1<<MUX5;
#else
@ -997,13 +1114,13 @@ ISR(TIMER0_COMPB_vect)
temp_state = 3;
break;
case 3: // Measure TEMP_BED
#if (TEMP_BED_PIN > -1)
#if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
raw_temp_bed_value += ADC;
#endif
temp_state = 4;
break;
case 4: // Prepare TEMP_1
#if (TEMP_1_PIN > -1)
#if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
#if TEMP_1_PIN > 7
ADCSRB = 1<<MUX5;
#else
@ -1016,13 +1133,13 @@ ISR(TIMER0_COMPB_vect)
temp_state = 5;
break;
case 5: // Measure TEMP_1
#if (TEMP_1_PIN > -1)
#if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
raw_temp_1_value += ADC;
#endif
temp_state = 6;
break;
case 6: // Prepare TEMP_2
#if (TEMP_2_PIN > -1)
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
#if TEMP_2_PIN > 7
ADCSRB = 1<<MUX5;
#else
@ -1035,7 +1152,7 @@ ISR(TIMER0_COMPB_vect)
temp_state = 7;
break;
case 7: // Measure TEMP_2
#if (TEMP_2_PIN > -1)
#if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
raw_temp_2_value += ADC;
#endif
temp_state = 0;
@ -1055,6 +1172,9 @@ ISR(TIMER0_COMPB_vect)
#if EXTRUDERS > 1
current_temperature_raw[1] = raw_temp_1_value;
#endif
#ifdef TEMP_SENSOR_1_AS_REDUNDANT
redundant_temperature_raw = raw_temp_1_value;
#endif
#if EXTRUDERS > 2
current_temperature_raw[2] = raw_temp_2_value;
#endif