Lots of minor tweaks during some test runs, most notable is that tail of dda_step routing is now interruptible
This commit is contained in:
parent
fe9938bcef
commit
f8eee368c4
|
|
@ -36,7 +36,7 @@ CC = $(ARCH)gcc
|
|||
OBJDUMP = $(ARCH)objdump
|
||||
OBJCOPY = $(ARCH)objcopy
|
||||
|
||||
OPTIMIZE = -Os -ffunction-sections -finline-functions-called-once -DDEBUG=1
|
||||
OPTIMIZE = -Os -ffunction-sections -finline-functions-called-once -DDEBUG=0
|
||||
# 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
|
||||
LDFLAGS = -Wl,--as-needed -Wl,--gc-sections
|
||||
|
|
@ -66,7 +66,7 @@ program: $(PROGRAM).hex
|
|||
@sleep 0.1
|
||||
@stty $(PROGBAUD) raw ignbrk hup < $(PROGPORT)
|
||||
$(AVRDUDE) -cstk500v1 -b$(PROGBAUD) -p$(MCU_TARGET) -P$(PROGPORT) -C/etc/avrdude.conf -U flash:w:$^
|
||||
stty 115200 raw ignbrk -hup -echo ixon < $(PROGPORT)
|
||||
stty 38400 raw ignbrk -hup -echo ixon < $(PROGPORT)
|
||||
|
||||
clean:
|
||||
rm -rf *.o *.elf *.lst *.map *.sym *.lss *.eep *.srec *.bin *.hex *.al *.i *.s *~
|
||||
|
|
|
|||
|
|
@ -1,6 +1,7 @@
|
|||
#include "dda.h"
|
||||
|
||||
#include <string.h>
|
||||
#include <avr/interrupt.h>
|
||||
|
||||
#include "timer.h"
|
||||
#include "serial.h"
|
||||
|
|
@ -375,6 +376,10 @@ void dda_step(DDA *dda) {
|
|||
}
|
||||
}
|
||||
|
||||
// this interrupt can now be interruptible
|
||||
disableTimerInterrupt();
|
||||
sei();
|
||||
|
||||
// this generates too much debug output for all but the slowest step rates
|
||||
if (0 && DEBUG) {
|
||||
serial_writechar('[');
|
||||
|
|
@ -413,4 +418,8 @@ void dda_step(DDA *dda) {
|
|||
// turn off step outputs, hopefully they've been on long enough by now to register with the drivers
|
||||
// if not, too bad. or insert a (very!) small delay here, or fire up a spare timer or something
|
||||
unstep();
|
||||
|
||||
// reset interruptible so we can return in the same state we started
|
||||
cli();
|
||||
enableTimerInterrupt();
|
||||
}
|
||||
|
|
|
|||
|
|
@ -109,12 +109,12 @@ void scan_char(uint8_t c) {
|
|||
switch (last_field) {
|
||||
case 'G':
|
||||
next_target.G = read_digit.mantissa;
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_uint8(next_target.G);
|
||||
break;
|
||||
case 'M':
|
||||
next_target.M = read_digit.mantissa;
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_uint8(next_target.M);
|
||||
break;
|
||||
case 'X':
|
||||
|
|
@ -122,7 +122,7 @@ void scan_char(uint8_t c) {
|
|||
next_target.target.X = decfloat_to_int(&read_digit, STEPS_PER_IN_X, 1);
|
||||
else
|
||||
next_target.target.X = decfloat_to_int(&read_digit, STEPS_PER_MM_X, 1);
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_int32(next_target.target.X);
|
||||
break;
|
||||
case 'Y':
|
||||
|
|
@ -130,7 +130,7 @@ void scan_char(uint8_t c) {
|
|||
next_target.target.Y = decfloat_to_int(&read_digit, STEPS_PER_IN_Y, 1);
|
||||
else
|
||||
next_target.target.Y = decfloat_to_int(&read_digit, STEPS_PER_MM_Y, 1);
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_int32(next_target.target.Y);
|
||||
break;
|
||||
case 'Z':
|
||||
|
|
@ -138,7 +138,7 @@ void scan_char(uint8_t c) {
|
|||
next_target.target.Z = decfloat_to_int(&read_digit, STEPS_PER_IN_Z, 1);
|
||||
else
|
||||
next_target.target.Z = decfloat_to_int(&read_digit, STEPS_PER_MM_Z, 1);
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_int32(next_target.target.Z);
|
||||
break;
|
||||
case 'E':
|
||||
|
|
@ -146,7 +146,7 @@ void scan_char(uint8_t c) {
|
|||
next_target.target.E = decfloat_to_int(&read_digit, STEPS_PER_IN_E, 1);
|
||||
else
|
||||
next_target.target.E = decfloat_to_int(&read_digit, STEPS_PER_MM_E, 1);
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_uint32(next_target.target.E);
|
||||
break;
|
||||
case 'F':
|
||||
|
|
@ -155,7 +155,7 @@ void scan_char(uint8_t c) {
|
|||
next_target.target.F = decfloat_to_int(&read_digit, 254, 10);
|
||||
else
|
||||
next_target.target.F = decfloat_to_int(&read_digit, 1, 1);
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_uint32(next_target.target.F);
|
||||
break;
|
||||
case 'S':
|
||||
|
|
@ -169,7 +169,7 @@ void scan_char(uint8_t c) {
|
|||
next_target.S = decfloat_to_int(&read_digit, PID_SCALE, 1);
|
||||
else
|
||||
next_target.S = decfloat_to_int(&read_digit, 1, 1);
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_uint16(next_target.S);
|
||||
break;
|
||||
case 'P':
|
||||
|
|
@ -178,7 +178,7 @@ void scan_char(uint8_t c) {
|
|||
next_target.P = decfloat_to_int(&read_digit, 1000, 1);
|
||||
else
|
||||
next_target.P = decfloat_to_int(&read_digit, 1, 1);
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serwrite_uint16(next_target.P);
|
||||
break;
|
||||
}
|
||||
|
|
@ -195,7 +195,7 @@ void scan_char(uint8_t c) {
|
|||
// new field?
|
||||
if (indexof(c, alphabet) >= 0) {
|
||||
last_field = c;
|
||||
if (DEBUG)
|
||||
// if (DEBUG)
|
||||
serial_writechar(c);
|
||||
}
|
||||
|
||||
|
|
@ -264,21 +264,24 @@ void scan_char(uint8_t c) {
|
|||
|
||||
// end of line
|
||||
if ((c == 10) || (c == 13)) {
|
||||
serial_writechar(c);
|
||||
// if (DEBUG)
|
||||
serial_writechar(c);
|
||||
// process
|
||||
process_gcode_command(&next_target);
|
||||
// if (next_target.seen_G || next_target.seen_M) {
|
||||
process_gcode_command(&next_target);
|
||||
|
||||
// reset 'seen comment'
|
||||
option_bitfield &= ~OPTION_COMMENT;
|
||||
// reset 'seen comment'
|
||||
option_bitfield &= ~OPTION_COMMENT;
|
||||
|
||||
// reset variables
|
||||
next_target.seen_X = next_target.seen_Y = next_target.seen_Z = next_target.seen_E = next_target.seen_F = next_target.seen_S = next_target.seen_P = 0;
|
||||
last_field = 0;
|
||||
read_digit.sign = 0;
|
||||
read_digit.mantissa = 0;
|
||||
read_digit.exponent = 0;
|
||||
// reset variables
|
||||
next_target.seen_X = next_target.seen_Y = next_target.seen_Z = next_target.seen_E = next_target.seen_F = next_target.seen_S = next_target.seen_P = 0;
|
||||
last_field = 0;
|
||||
read_digit.sign = 0;
|
||||
read_digit.mantissa = 0;
|
||||
read_digit.exponent = 0;
|
||||
|
||||
serial_writestr_P(PSTR("OK\n"));
|
||||
serial_writestr_P(PSTR("OK\n"));
|
||||
// }
|
||||
}
|
||||
}
|
||||
|
||||
|
|
@ -423,6 +426,7 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
|
|||
switch (gcmd->M) {
|
||||
// M101- extruder on
|
||||
case 101:
|
||||
serial_writestr_P(PSTR("Waiting for extruder to reach target temperature\n"));
|
||||
// here we wait until target temperature is reached, and emulate main loop so the temperature can actually be updated
|
||||
while (!temp_achieved()) {
|
||||
ifclock(CLOCK_FLAG_250MS) {
|
||||
|
|
|
|||
|
|
@ -47,7 +47,7 @@
|
|||
#define E_STARTSTOP_STEPS 20
|
||||
|
||||
// extruder settings
|
||||
#define TEMP_HYSTERESIS 2
|
||||
#define TEMP_HYSTERESIS 20
|
||||
|
||||
/*
|
||||
calculated values - you shouldn't need to touch these
|
||||
|
|
|
|||
|
|
@ -40,10 +40,10 @@ inline void io_init(void) {
|
|||
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);
|
||||
TCCR0A = MASK(WGM01) | MASK(WGM00);
|
||||
TCCR0B = MASK(CS00);
|
||||
TIMSK0 = 0;
|
||||
OCR0A = 0;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
|
@ -55,7 +55,9 @@ inline void io_init(void) {
|
|||
disable_steppers();
|
||||
#endif
|
||||
|
||||
// setup SPI
|
||||
WRITE(SCK, 0); SET_OUTPUT(SCK);
|
||||
WRITE(MOSI, 1); SET_OUTPUT(MOSI);
|
||||
WRITE(MISO, 1); SET_INPUT(MISO);
|
||||
WRITE(SS, 1); SET_OUTPUT(SS);
|
||||
}
|
||||
|
|
@ -135,9 +137,9 @@ void clock_250ms() {
|
|||
// Queue
|
||||
print_queue();
|
||||
}
|
||||
|
||||
// temperature
|
||||
temp_print();
|
||||
if (temp_get_target())
|
||||
temp_print();
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -14,6 +14,10 @@
|
|||
|
||||
#define RESERVED_RXD DIO0
|
||||
#define RESERVED_TXD DIO1
|
||||
#define RESERVED_SCK DIO13
|
||||
#define RESERVED_MISO DIO12
|
||||
#define RESERVED_MOSI DIO11
|
||||
#define RESERVED_SS DIO10
|
||||
|
||||
/*
|
||||
user defined pins
|
||||
|
|
@ -108,8 +112,8 @@
|
|||
*/
|
||||
|
||||
#ifdef HEATER_PWM
|
||||
#define enable_heater() do { OCR0A = 255; } while (0)
|
||||
#define disable_heater() do { OCR0A = 0; } while (0)
|
||||
#define enable_heater() do { TCCR0A |= MASK(COM0A1); } while (0)
|
||||
#define disable_heater() do { TCCR0A &= ~MASK(COM0A1); } while (0)
|
||||
#else
|
||||
#define enable_heater() WRITE(HEATER_PIN, 1)
|
||||
#define disable_heater() WRITE(HEATER_PIN, 0)
|
||||
|
|
|
|||
|
|
@ -4,7 +4,7 @@
|
|||
#include "arduino.h"
|
||||
|
||||
#define BUFSIZE 64 + sizeof(ringbuffer)
|
||||
#define BAUD 115200
|
||||
#define BAUD 38400
|
||||
|
||||
#define ASCII_XOFF 19
|
||||
#define ASCII_XON 17
|
||||
|
|
|
|||
|
|
@ -43,37 +43,28 @@ uint8_t temp_flags = 0;
|
|||
uint16_t temp_read() {
|
||||
uint16_t temp;
|
||||
|
||||
/* if (DEBUG)
|
||||
serial_writestr_P(PSTR("T["));*/
|
||||
|
||||
// very slow for debugging
|
||||
SPCR = MASK(MSTR) | MASK(SPE) | MASK(SPR1) | MASK(SPR0);
|
||||
SPCR = MASK(MSTR) | MASK(SPE) | MASK(SPR0);
|
||||
|
||||
// enable MAX6675
|
||||
WRITE(SS, 0);
|
||||
|
||||
// ensure 100ns delay - a bit extra is fine
|
||||
delay(1);
|
||||
|
||||
// read MSB
|
||||
SPDR = 0;
|
||||
for (;(SPSR & MASK(SPIF)) == 0;);
|
||||
temp = SPDR;
|
||||
|
||||
// if (DEBUG)
|
||||
// serwrite_hex8(temp & 0xFF);
|
||||
|
||||
temp <<= 8;
|
||||
|
||||
// read LSB
|
||||
SPDR = 0;
|
||||
for (;(SPSR & MASK(SPIF)) == 0;);
|
||||
temp |= SPDR;
|
||||
|
||||
// if (DEBUG)
|
||||
// serwrite_hex8(temp & 0xFF);
|
||||
|
||||
// disable MAX6675
|
||||
WRITE(SS, 1);
|
||||
|
||||
// turn off SPI system
|
||||
// SPCR = 0;
|
||||
|
||||
temp_flags = 0;
|
||||
if ((temp & 0x8002) == 0) {
|
||||
// got "device id"
|
||||
|
|
@ -134,7 +125,7 @@ void temp_print() {
|
|||
else {
|
||||
serial_writechar('0');
|
||||
}
|
||||
serial_writestr_P(PSTR("°C"));
|
||||
// serial_writestr_P(PSTR("°C"));
|
||||
}
|
||||
serial_writechar('\n');
|
||||
}
|
||||
|
|
@ -143,15 +134,15 @@ void temp_tick() {
|
|||
uint16_t last_temp = current_temp;
|
||||
temp_read();
|
||||
|
||||
if (DEBUG)
|
||||
serial_writestr_P(PSTR("T{"));
|
||||
// if (DEBUG)
|
||||
// serial_writestr_P(PSTR("T{"));
|
||||
|
||||
int16_t t_error = target_temp - current_temp;
|
||||
|
||||
if (DEBUG) {
|
||||
serial_writestr_P(PSTR("E:"));
|
||||
serwrite_int16(t_error);
|
||||
}
|
||||
// if (DEBUG) {
|
||||
// serial_writestr_P(PSTR("E:"));
|
||||
// serwrite_int16(t_error);
|
||||
// }
|
||||
|
||||
// PID stuff
|
||||
// proportional
|
||||
|
|
@ -187,10 +178,10 @@ void temp_tick() {
|
|||
else
|
||||
pid_output = (pid_output_intermed + 128);
|
||||
|
||||
if (DEBUG) {
|
||||
serial_writestr_P(PSTR("O:"));
|
||||
serwrite_uint8(pid_output);
|
||||
}
|
||||
// if (DEBUG) {
|
||||
// serial_writestr_P(PSTR(",O:"));
|
||||
// serwrite_uint8(pid_output);
|
||||
// }
|
||||
|
||||
#ifdef HEATER_PWM
|
||||
HEATER_PWM = pid_output;
|
||||
|
|
@ -203,6 +194,6 @@ void temp_tick() {
|
|||
}
|
||||
#endif
|
||||
|
||||
if (DEBUG)
|
||||
serial_writechar('}');
|
||||
// if (DEBUG)
|
||||
// serial_writechar('}');
|
||||
}
|
||||
|
|
|
|||
Loading…
Reference in New Issue