MAX6675 temperature code working, still playing with heater output, other fixes

This commit is contained in:
Michael Moon 2010-02-08 09:51:58 +11:00
parent 997ea730f4
commit 91c86beaf0
6 changed files with 102 additions and 27 deletions

View File

@ -36,8 +36,8 @@ CC = $(ARCH)gcc
OBJDUMP = $(ARCH)objdump OBJDUMP = $(ARCH)objdump
OBJCOPY = $(ARCH)objcopy OBJCOPY = $(ARCH)objcopy
# OPTIMIZE = -Os -ffunction-sections -finline-functions-called-once -DDEBUG=1 OPTIMIZE = -Os -ffunction-sections -finline-functions-called-once -DDEBUG=1
OPTIMIZE = -O0 # OPTIMIZE = -O0
CFLAGS = -g -Wall -Wstrict-prototypes $(OPTIMIZE) -mmcu=$(MCU_TARGET) -DF_CPU=$(F_CPU) $(DEFS) -std=gnu99 -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -save-temps CFLAGS = -g -Wall -Wstrict-prototypes $(OPTIMIZE) -mmcu=$(MCU_TARGET) -DF_CPU=$(F_CPU) $(DEFS) -std=gnu99 -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -save-temps
LDFLAGS = -Wl,--as-needed -Wl,--gc-sections LDFLAGS = -Wl,--as-needed -Wl,--gc-sections

View File

@ -444,6 +444,8 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
// M104- set temperature // M104- set temperature
case 104: case 104:
temp_set(gcmd->S); temp_set(gcmd->S);
enable_heater();
enable_steppers();
break; break;
// M105- get temperature // M105- get temperature

View File

@ -36,13 +36,15 @@ inline void io_init(void) {
WRITE(E_STEP_PIN, 0); SET_OUTPUT(E_STEP_PIN); WRITE(E_STEP_PIN, 0); SET_OUTPUT(E_STEP_PIN);
WRITE(E_DIR_PIN, 0); SET_OUTPUT(E_DIR_PIN); WRITE(E_DIR_PIN, 0); SET_OUTPUT(E_DIR_PIN);
// setup PWM timer: phase-correct PWM, no prescaler, no outputs enabled yet
TCCR0A = MASK(WGM00);
TCCR0B = MASK(CS00);
TIMSK0 = 0;
#ifdef HEATER_PIN #ifdef HEATER_PIN
disable_heater(); WRITE(HEATER_PIN, 0); SET_OUTPUT(HEATER_PIN);
#ifdef HEATER_PWM
// setup PWM timer: fast PWM, no prescaler
OCR0A = 0;
TCCR0A = MASK(COM0A1) | MASK(WGM01) | MASK(WGM00);
TCCR0B = MASK(CS00);
TIMSK0 = 0;
#endif
#endif #endif
#ifdef FAN_PIN #ifdef FAN_PIN
@ -53,12 +55,13 @@ inline void io_init(void) {
disable_steppers(); disable_steppers();
#endif #endif
WRITE(SCK, 1); SET_OUTPUT(SCK); WRITE(SCK, 0); SET_OUTPUT(SCK);
WRITE(MISO, 1); SET_INPUT(MISO); WRITE(MISO, 1); SET_INPUT(MISO);
WRITE(SS, 0); SET_OUTPUT(SS); WRITE(SS, 1); SET_OUTPUT(SS);
} }
inline void init(void) { inline void init(void);
inline void init() {
// set up serial // set up serial
serial_init(); serial_init();
@ -87,8 +90,10 @@ void clock_250ms(void);
void clock_250ms() { void clock_250ms() {
temp_tick(); temp_tick();
if (steptimeout > (30 * 4)) if (steptimeout > (30 * 4)) {
disable_steppers(); if (temp_get_target() == 0)
disable_steppers();
}
else else
steptimeout++; steptimeout++;

View File

@ -48,7 +48,7 @@
// OC2B DIO3 // OC2B DIO3
#define HEATER_PIN DIO6 #define HEATER_PIN DIO6
#define HEATER_PIN_PWM OC0A #define HEATER_PWM OCR0A
// #define FAN_PIN DIO5 // #define FAN_PIN DIO5
// #define FAN_PIN_PWM OC0B // #define FAN_PIN_PWM OC0B
@ -107,12 +107,12 @@
Heater Heater
*/ */
#ifdef HEATER_PIN_PWM #ifdef HEATER_PWM
#define enable_heater() WRITE(HEATER_PIN, 1) #define enable_heater() do { OCR0A = 255; } while (0)
#define disable_heater() do { WRITE(HEATER_PIN, 0); } while (0) #define disable_heater() do { OCR0A = 0; } while (0)
#else #else
#define enable_heater() do { TCCR0A = (TCCR0A & MASK(COM0A0)) | MASK(COM0A1); SET_OUTPUT(HEATER_PIN); } while (0) #define enable_heater() WRITE(HEATER_PIN, 1)
#define disable_heater() do { WRITE(HEATER_PIN, 0); HEATER_PIN_PWM = 0; TCCR0A &= ~(MASK(COM0A0) | MASK(COM0A1)); SET_OUTPUT(HEATER_PIN); } while (0) #define disable_heater() WRITE(HEATER_PIN, 0)
#endif #endif
/* /*

View File

@ -23,6 +23,7 @@
#include "clock.h" #include "clock.h"
#include "serial.h" #include "serial.h"
#include "sermsg.h" #include "sermsg.h"
#include "timer.h"
uint16_t current_temp = 0; uint16_t current_temp = 0;
uint16_t target_temp = 0; uint16_t target_temp = 0;
@ -41,21 +42,37 @@ uint8_t temp_flags = 0;
uint16_t temp_read() { uint16_t temp_read() {
uint16_t temp; uint16_t temp;
SPCR = MASK(MSTR) | MASK(SPE);
WRITE(SS, 1); /* if (DEBUG)
serial_writestr_P(PSTR("T["));*/
// very slow for debugging
SPCR = MASK(MSTR) | MASK(SPE) | MASK(SPR1) | MASK(SPR0);
WRITE(SS, 0);
delay(1);
SPDR = 0; SPDR = 0;
for (;(SPSR & MASK(SPIF)) == 0;); for (;(SPSR & MASK(SPIF)) == 0;);
temp = SPDR << 8; temp = SPDR;
// if (DEBUG)
// serwrite_hex8(temp & 0xFF);
temp <<= 8;
SPDR = 0; SPDR = 0;
for (;(SPSR & MASK(SPIF)) == 0;); for (;(SPSR & MASK(SPIF)) == 0;);
temp |= SPDR; temp |= SPDR;
WRITE(SS, 0); // if (DEBUG)
// serwrite_hex8(temp & 0xFF);
SPCR = 0; WRITE(SS, 1);
// turn off SPI system
// SPCR = 0;
temp_flags = 0; temp_flags = 0;
if ((temp & 0x8002) == 0) { if ((temp & 0x8002) == 0) {
@ -71,6 +88,9 @@ uint16_t temp_read() {
} }
} }
// if (DEBUG)
// serial_writechar(']');
return 0; return 0;
} }
@ -82,6 +102,10 @@ uint16_t temp_get() {
return current_temp; return current_temp;
} }
uint16_t temp_get_target() {
return target_temp;
}
uint8_t temp_achieved() { uint8_t temp_achieved() {
if (current_temp >= target_temp) if (current_temp >= target_temp)
if ((current_temp - target_temp) < TEMP_HYSTERESIS) if ((current_temp - target_temp) < TEMP_HYSTERESIS)
@ -98,7 +122,18 @@ void temp_print() {
serial_writestr_P(PSTR("no thermocouple!")); serial_writestr_P(PSTR("no thermocouple!"));
} }
else { else {
serwrite_uint16(temp_get()); serwrite_uint16(temp_get() >> 2);
serial_writechar('.');
if (current_temp) {
if ((current_temp & 3) == 3)
serial_writechar('7');
else if ((current_temp & 3) == 1)
serial_writechar('2');
serial_writechar('5');
}
else {
serial_writechar('0');
}
serial_writestr_P(PSTR("°C")); serial_writestr_P(PSTR("°C"));
} }
serial_writechar('\n'); serial_writechar('\n');
@ -108,8 +143,16 @@ void temp_tick() {
uint16_t last_temp = current_temp; uint16_t last_temp = current_temp;
temp_read(); temp_read();
if (DEBUG)
serial_writestr_P(PSTR("T{"));
int16_t t_error = target_temp - current_temp; int16_t t_error = target_temp - current_temp;
if (DEBUG) {
serial_writestr_P(PSTR("E:"));
serwrite_int16(t_error);
}
// PID stuff // PID stuff
// proportional // proportional
heater_p = t_error; heater_p = t_error;
@ -144,8 +187,13 @@ void temp_tick() {
else else
pid_output = (pid_output_intermed + 128); pid_output = (pid_output_intermed + 128);
#ifdef HEATER_PIN_PWMABLE if (DEBUG) {
HEATER_PIN_PWMABLE = pid_output serial_writestr_P(PSTR("O:"));
serwrite_uint8(pid_output);
}
#ifdef HEATER_PWM
HEATER_PWM = pid_output;
#else #else
if (pid_output >= 128) { if (pid_output >= 128) {
enable_heater(); enable_heater();
@ -154,4 +202,7 @@ void temp_tick() {
disable_heater(); disable_heater();
} }
#endif #endif
if (DEBUG)
serial_writechar('}');
} }

View File

@ -12,6 +12,20 @@ extern int32_t d_factor;
#define PID_SCALE 1024L #define PID_SCALE 1024L
#define I_LIMIT 4000 #define I_LIMIT 4000
typedef union {
struct {
uint8_t high;
uint8_t low;
} buf;
struct {
uint16_t dummy :1;
uint16_t reading :12;
uint16_t tc_open :1;
uint16_t device_id :1;
uint16_t tristate :1;
} interpret;
} max6675_data_format;
// read temperature from sensor // read temperature from sensor
uint16_t temp_read(void); uint16_t temp_read(void);
@ -21,6 +35,9 @@ void temp_set(uint16_t t);
// return last read temperature // return last read temperature
uint16_t temp_get(void); uint16_t temp_get(void);
// return target temperature
uint16_t temp_get_target(void);
// true if last read temp is close to target temp, false otherwise // true if last read temp is close to target temp, false otherwise
uint8_t temp_achieved(void); uint8_t temp_achieved(void);