From 2c42dc512191953397bf19011434646b63ec70de Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 2 Oct 2015 23:13:23 -0700 Subject: [PATCH] Keep "astyled" elements in temperature.* --- Marlin/temperature.cpp | 155 +++++++++++++++++++++-------------------- Marlin/temperature.h | 32 ++++----- 2 files changed, 95 insertions(+), 92 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 9c45d1050b..4b5f662bf8 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -1,19 +1,19 @@ /* temperature.cpp - temperature control Part of Marlin - + Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm - + 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 . */ @@ -54,28 +54,28 @@ float current_temperature_bed = 0.0; #endif #if ENABLED(PIDTEMPBED) - float bedKp=DEFAULT_bedKp; - float bedKi=(DEFAULT_bedKi*PID_dT); - float bedKd=(DEFAULT_bedKd/PID_dT); + float bedKp = DEFAULT_bedKp; + float bedKi = (DEFAULT_bedKi* PID_dT); + float bedKd = (DEFAULT_bedKd / PID_dT); #endif //PIDTEMPBED - + #if ENABLED(FAN_SOFT_PWM) unsigned char fanSpeedSoftPwm; #endif unsigned char soft_pwm_bed; - + #if ENABLED(BABYSTEPPING) volatile int babystepsTodo[3] = { 0 }; #endif #if ENABLED(FILAMENT_SENSOR) int current_raw_filwidth = 0; //Holds measured filament diameter - one extruder only -#endif +#endif #if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED) enum TRState { TRReset, TRInactive, TRFirstHeating, TRStable, TRRunaway }; - void thermal_runaway_protection(TRState *state, millis_t *timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc); + void thermal_runaway_protection(TRState* state, millis_t* timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc); #if ENABLED(THERMAL_PROTECTION_HOTENDS) static TRState thermal_runaway_state_machine[4] = { TRReset, TRReset, TRReset, TRReset }; static millis_t thermal_runaway_timer[4]; // = {0,0,0,0}; @@ -125,19 +125,19 @@ static volatile bool temp_meas_ready = false; #else //PIDTEMPBED static millis_t next_bed_check_ms; #endif //PIDTEMPBED - static unsigned char soft_pwm[EXTRUDERS]; +static unsigned char soft_pwm[EXTRUDERS]; #if ENABLED(FAN_SOFT_PWM) static unsigned char soft_pwm_fan; #endif #if HAS_AUTO_FAN static millis_t next_auto_fan_check_ms; -#endif +#endif #if ENABLED(PIDTEMP) #if ENABLED(PID_PARAMS_PER_EXTRUDER) float Kp[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Kp); - float Ki[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Ki*PID_dT); + float Ki[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Ki* PID_dT); float Kd[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Kd / PID_dT); #if ENABLED(PID_ADD_EXTRUSION_RATE) float Kc[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_Kc); @@ -153,23 +153,23 @@ static volatile bool temp_meas_ready = false; #endif //PIDTEMP // Init min and max temp with extreme values to prevent false errors during startup -static int minttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP, HEATER_3_RAW_LO_TEMP); -static int maxttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP, HEATER_3_RAW_HI_TEMP); +static int minttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS(HEATER_0_RAW_LO_TEMP , HEATER_1_RAW_LO_TEMP , HEATER_2_RAW_LO_TEMP, HEATER_3_RAW_LO_TEMP); +static int maxttemp_raw[EXTRUDERS] = ARRAY_BY_EXTRUDERS(HEATER_0_RAW_HI_TEMP , HEATER_1_RAW_HI_TEMP , HEATER_2_RAW_HI_TEMP, HEATER_3_RAW_HI_TEMP); static int minttemp[EXTRUDERS] = { 0 }; static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(16383); #ifdef BED_MINTEMP -static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP; + static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP; #endif #ifdef BED_MAXTEMP static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP; #endif #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static void *heater_ttbl_map[2] = {(void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE }; + 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, (void *)HEATER_3_TEMPTABLE ); - static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN, HEATER_3_TEMPTABLE_LEN ); + static void* heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS((void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE, (void*)HEATER_2_TEMPTABLE, (void*)HEATER_3_TEMPTABLE); + static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS(HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN, HEATER_3_TEMPTABLE_LEN); #endif static float analog2temp(int raw, uint8_t e); @@ -240,7 +240,7 @@ void PID_autotune(float temp, int extruder, int ncycles) { if (temp_meas_ready) { // temp sample ready updateTemperaturesFromRawValues(); - input = (extruder<0)?current_temperature_bed:current_temperature[extruder]; + input = (extruder < 0) ? current_temperature_bed : current_temperature[extruder]; max = max(max, input); min = min(min, input); @@ -272,7 +272,7 @@ void PID_autotune(float temp, int extruder, int ncycles) { t_low = t2 - t1; if (cycles > 0) { long max_pow = extruder < 0 ? MAX_BED_POWER : PID_MAX; - bias += (d*(t_high - t_low))/(t_low + t_high); + 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; @@ -317,7 +317,7 @@ void PID_autotune(float temp, int extruder, int ncycles) { cycles++; min = temp; } - } + } } #define MAX_OVERSHOOT_PID_AUTOTUNE 20 if (input > temp + MAX_OVERSHOOT_PID_AUTOTUNE) { @@ -343,13 +343,13 @@ void PID_autotune(float temp, int extruder, int ncycles) { temp_ms = ms; } // every 2 seconds // Over 2 minutes? - if (((ms - t1) + (ms - t2)) > (10L*60L*1000L*2L)) { + if (((ms - t1) + (ms - t2)) > (10L * 60L * 1000L * 2L)) { SERIAL_PROTOCOLLNPGM(MSG_PID_TIMEOUT); return; } if (cycles > ncycles) { SERIAL_PROTOCOLLNPGM(MSG_PID_AUTOTUNE_FINISHED); - const char *estring = extruder < 0 ? "bed" : ""; + const char* estring = extruder < 0 ? "bed" : ""; SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Kp "); SERIAL_PROTOCOLLN(Kp); SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Ki "); SERIAL_PROTOCOLLN(Ki); SERIAL_PROTOCOLPGM("#define DEFAULT_"); SERIAL_PROTOCOL(estring); SERIAL_PROTOCOLPGM("Kd "); SERIAL_PROTOCOLLN(Kd); @@ -391,12 +391,11 @@ void checkExtruderAutoFans() { // which fan pins need to be turned on? #if HAS_AUTO_FAN_0 - if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE) + if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE) fanState |= 1; #endif #if HAS_AUTO_FAN_1 - if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) - { + if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) { if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) fanState |= 1; else @@ -404,24 +403,22 @@ void checkExtruderAutoFans() { } #endif #if HAS_AUTO_FAN_2 - if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE) - { - if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) + 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) + else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN) fanState |= 2; else fanState |= 4; } #endif #if HAS_AUTO_FAN_3 - if (current_temperature[3] > EXTRUDER_AUTO_FAN_TEMPERATURE) - { - if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) + if (current_temperature[3] > EXTRUDER_AUTO_FAN_TEMPERATURE) { + if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) fanState |= 1; - else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN) + else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN) fanState |= 2; - else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN) + else if (EXTRUDER_3_AUTO_FAN_PIN == EXTRUDER_2_AUTO_FAN_PIN) fanState |= 4; else fanState |= 8; @@ -454,7 +451,7 @@ void checkExtruderAutoFans() { // // Temperature Error Handlers // -inline void _temp_error(int e, const char *serial_msg, const char *lcd_msg) { +inline void _temp_error(int e, const char* serial_msg, const char* lcd_msg) { static bool killed = false; if (IsRunning()) { SERIAL_ERROR_START; @@ -485,7 +482,7 @@ float get_pid_output(int e) { #if ENABLED(PIDTEMP) #if DISABLED(PID_OPENLOOP) pid_error[e] = target_temperature[e] - current_temperature[e]; - dTerm[e] = K2 * PID_PARAM(Kd,e) * (current_temperature[e] - temp_dState[e]) + K1 * dTerm[e]; + dTerm[e] = K2 * PID_PARAM(Kd, e) * (current_temperature[e] - temp_dState[e]) + K1 * dTerm[e]; temp_dState[e] = current_temperature[e]; if (pid_error[e] > PID_FUNCTIONAL_RANGE) { pid_output = BANG_MAX; @@ -500,10 +497,10 @@ float get_pid_output(int e) { temp_iState[e] = 0.0; pid_reset[e] = false; } - pTerm[e] = PID_PARAM(Kp,e) * pid_error[e]; + pTerm[e] = PID_PARAM(Kp, e) * pid_error[e]; temp_iState[e] += pid_error[e]; temp_iState[e] = constrain(temp_iState[e], temp_iState_min[e], temp_iState_max[e]); - iTerm[e] = PID_PARAM(Ki,e) * temp_iState[e]; + iTerm[e] = PID_PARAM(Ki, e) * temp_iState[e]; pid_output = pTerm[e] + iTerm[e] - dTerm[e]; @@ -669,7 +666,7 @@ void manage_heater() { checkExtruderAutoFans(); next_auto_fan_check_ms = ms + 2500; } - #endif + #endif // Control the extruder rate based on the width sensor #if ENABLED(FILAMENT_SENSOR) @@ -742,7 +739,7 @@ static float analog2temp(int raw, uint8_t e) { SERIAL_ERRORLNPGM(MSG_INVALID_EXTRUDER_NUM); kill(PSTR(MSG_KILLED)); return 0.0; - } + } #if ENABLED(HEATER_0_USES_MAX6675) if (e == 0) return 0.25 * raw; @@ -751,20 +748,20 @@ static float analog2temp(int raw, uint8_t e) { if (heater_ttbl_map[e] != NULL) { float celsius = 0; uint8_t i; - short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]); + short(*tt)[][2] = (short(*)[][2])(heater_ttbl_map[e]); for (i = 1; i < heater_ttbllen_map[e]; i++) { if (PGM_RD_W((*tt)[i][0]) > raw) { - celsius = PGM_RD_W((*tt)[i-1][1]) + - (raw - PGM_RD_W((*tt)[i-1][0])) * - (float)(PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i-1][1])) / - (float)(PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i-1][0])); + celsius = PGM_RD_W((*tt)[i - 1][1]) + + (raw - PGM_RD_W((*tt)[i - 1][0])) * + (float)(PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i - 1][1])) / + (float)(PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i - 1][0])); break; } } // Overflow: Set to last value in the table - if (i == heater_ttbllen_map[e]) celsius = PGM_RD_W((*tt)[i-1][1]); + if (i == heater_ttbllen_map[e]) celsius = PGM_RD_W((*tt)[i - 1][1]); return celsius; } @@ -780,22 +777,27 @@ static float analog2tempBed(int raw) { for (i = 1; i < BEDTEMPTABLE_LEN; i++) { if (PGM_RD_W(BEDTEMPTABLE[i][0]) > raw) { - celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]) + - (raw - PGM_RD_W(BEDTEMPTABLE[i-1][0])) * - (float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i-1][1])) / - (float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i-1][0])); + celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]) + + (raw - PGM_RD_W(BEDTEMPTABLE[i - 1][0])) * + (float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i - 1][1])) / + (float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i - 1][0])); break; } } // Overflow: Set to last value in the table - if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]); + if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]); return celsius; - #elif defined BED_USES_AD595 + + #elif defined(BED_USES_AD595) + return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET; + #else + return 0; + #endif } @@ -850,17 +852,17 @@ static void updateTemperaturesFromRawValues() { void tp_init() { #if MB(RUMBA) && ((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=BIT(JTD); - MCUCR=BIT(JTD); + MCUCR = BIT(JTD); + MCUCR = BIT(JTD); #endif // Finish init of mult extruder arrays for (int e = 0; e < EXTRUDERS; e++) { - // populate with the first value + // populate with the first value maxttemp[e] = maxttemp[0]; #if ENABLED(PIDTEMP) temp_iState_min[e] = 0.0; - temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / PID_PARAM(Ki,e); + temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / PID_PARAM(Ki, e); #if ENABLED(PID_ADD_EXTRUSION_RATE) last_position[e] = 0; #endif @@ -885,7 +887,7 @@ void tp_init() { #endif #if HAS_HEATER_BED SET_OUTPUT(HEATER_BED_PIN); - #endif + #endif #if HAS_FAN SET_OUTPUT(FAN_PIN); #if ENABLED(FAST_PWM_FAN) @@ -907,7 +909,7 @@ void tp_init() { digitalWrite(SS_PIN, HIGH); #endif - OUT_WRITE(MAX6675_SS,HIGH); + OUT_WRITE(MAX6675_SS, HIGH); #endif //HEATER_0_USES_MAX6675 @@ -958,8 +960,8 @@ void tp_init() { // Use timer0 for temperature measurement // Interleave temperature interrupt with millies interrupt OCR0B = 128; - TIMSK0 |= BIT(OCIE0B); - + TIMSK0 |= BIT(OCIE0B); + // Wait for temperature measurement to settle delay(250); @@ -1021,7 +1023,7 @@ void tp_init() { } #endif //BED_MINTEMP #ifdef BED_MAXTEMP - while(analog2tempBed(bed_maxttemp_raw) > BED_MAXTEMP) { + while (analog2tempBed(bed_maxttemp_raw) > BED_MAXTEMP) { #if HEATER_BED_RAW_LO_TEMP < HEATER_BED_RAW_HI_TEMP bed_maxttemp_raw -= OVERSAMPLENR; #else @@ -1049,9 +1051,9 @@ void tp_init() { #if ENABLED(THERMAL_PROTECTION_HOTENDS) || ENABLED(THERMAL_PROTECTION_BED) - void thermal_runaway_protection(TRState *state, millis_t *timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc) { + void thermal_runaway_protection(TRState* state, millis_t* timer, float temperature, float target_temperature, int heater_id, int period_seconds, int hysteresis_degc) { - static float tr_target_temperature[EXTRUDERS+1] = { 0.0 }; + static float tr_target_temperature[EXTRUDERS + 1] = { 0.0 }; /* SERIAL_ECHO_START; @@ -1094,7 +1096,7 @@ void tp_init() { // If the temperature is over the target (-hysteresis) restart the timer if (temperature >= tr_target_temperature[heater_index] - hysteresis_degc) *timer = millis(); - // If the timer goes too long without a reset, trigger shutdown + // If the timer goes too long without a reset, trigger shutdown else if (millis() > *timer + period_seconds * 1000UL) *state = TRRunaway; break; @@ -1106,7 +1108,7 @@ void tp_init() { #endif // THERMAL_PROTECTION_HOTENDS || THERMAL_PROTECTION_BED void disable_all_heaters() { - for (int i=0; i 1 if (soft_pwm_1 < pwm_count) WRITE_HEATER_1(0); #if EXTRUDERS > 2 @@ -1338,11 +1340,12 @@ ISR(TIMER0_COMPB_vect) { #if ENABLED(FAN_SOFT_PWM) if (soft_pwm_fan < pwm_count) WRITE_FAN(0); #endif - + pwm_count += BIT(SOFT_PWM_SCALE); pwm_count &= 0x7f; - + #else // SLOW_PWM_HEATERS + /* * SLOW PWM HEATERS * @@ -1454,7 +1457,7 @@ ISR(TIMER0_COMPB_vect) { #endif // Prepare or measure a sensor, each one every 12th frame - switch(temp_state) { + switch (temp_state) { case PrepareTemp_0: #if HAS_TEMP_0 START_ADC(TEMP_0_PIN); @@ -1536,8 +1539,8 @@ ISR(TIMER0_COMPB_vect) { #if HAS_FILAMENT_SENSOR // raw_filwidth_value += ADC; //remove to use an IIR filter approach if (ADC > 102) { //check that ADC is reading a voltage > 0.5 volts, otherwise don't take in the data. - raw_filwidth_value -= (raw_filwidth_value>>7); //multiply raw_filwidth_value by 127/128 - raw_filwidth_value += ((unsigned long)ADC<<7); //add new ADC reading + raw_filwidth_value -= (raw_filwidth_value >> 7); //multiply raw_filwidth_value by 127/128 + raw_filwidth_value += ((unsigned long)ADC << 7); //add new ADC reading } #endif temp_state = PrepareTemp_0; diff --git a/Marlin/temperature.h b/Marlin/temperature.h index ed18aaf5fd..29a6920ce9 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -19,7 +19,7 @@ */ #ifndef TEMPERATURE_H -#define TEMPERATURE_H +#define TEMPERATURE_H #include "Marlin.h" #include "planner.h" @@ -32,16 +32,16 @@ void tp_init(); //initialize the heating void manage_heater(); //it is critical that this is called periodically. #if ENABLED(FILAMENT_SENSOR) -// For converting raw Filament Width to milimeters - float analog2widthFil(); - -// For converting raw Filament Width to an extrusion ratio - int widthFil_to_size_ratio(); + // For converting raw Filament Width to milimeters + float analog2widthFil(); + + // For converting raw Filament Width to an extrusion ratio + int widthFil_to_size_ratio(); #endif // low level conversion routines // do not use these routines and variables outside of temperature.cpp -extern int target_temperature[4]; +extern int target_temperature[4]; extern float current_temperature[4]; #if ENABLED(SHOW_TEMP_ADC_VALUES) extern int current_temperature_raw[4]; @@ -65,7 +65,7 @@ extern float current_temperature_bed; #else extern float Kp, Ki, Kd, Kc; // one param per extruder - saves 20 or 36 bytes of ram (inc array pointer) #define PID_PARAM(param, e) param // use macro to point directly to value - #endif // PID_PARAMS_PER_EXTRUDER + #endif // PID_PARAMS_PER_EXTRUDER float scalePID_i(float i); float scalePID_d(float d); float unscalePID_i(float i); @@ -74,13 +74,13 @@ extern float current_temperature_bed; #endif #if ENABLED(PIDTEMPBED) - extern float bedKp,bedKi,bedKd; + extern float bedKp, bedKi, bedKd; #endif - + #if ENABLED(BABYSTEPPING) extern volatile int babystepsTodo[3]; #endif - + //high level conversion routines, for use outside of temperature.cpp //inline so that there is no performance decrease. //deg=degreeCelsius @@ -89,24 +89,24 @@ FORCE_INLINE float degHotend(uint8_t extruder) { return current_temperature[extr FORCE_INLINE float degBed() { return current_temperature_bed; } #if ENABLED(SHOW_TEMP_ADC_VALUES) - FORCE_INLINE float rawHotendTemp(uint8_t extruder) { return current_temperature_raw[extruder]; } - FORCE_INLINE float rawBedTemp() { return current_temperature_bed_raw; } +FORCE_INLINE float rawHotendTemp(uint8_t extruder) { return current_temperature_raw[extruder]; } +FORCE_INLINE float rawBedTemp() { return current_temperature_bed_raw; } #endif FORCE_INLINE float degTargetHotend(uint8_t extruder) { return target_temperature[extruder]; } FORCE_INLINE float degTargetBed() { return target_temperature_bed; } #if ENABLED(THERMAL_PROTECTION_HOTENDS) - void start_watching_heater(int e=0); + void start_watching_heater(int e = 0); #endif -FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) { +FORCE_INLINE void setTargetHotend(const float& celsius, uint8_t extruder) { target_temperature[extruder] = celsius; #if ENABLED(THERMAL_PROTECTION_HOTENDS) start_watching_heater(extruder); #endif } -FORCE_INLINE void setTargetBed(const float &celsius) { target_temperature_bed = celsius; } +FORCE_INLINE void setTargetBed(const float& celsius) { target_temperature_bed = celsius; } FORCE_INLINE bool isHeatingHotend(uint8_t extruder) { return target_temperature[extruder] > current_temperature[extruder]; } FORCE_INLINE bool isHeatingBed() { return target_temperature_bed > current_temperature_bed; }