time to save, looks like the DDA is working! NOTE: endstops disabled in dda.c lines 291-296 in this revision

This commit is contained in:
Michael Moon 2010-01-24 10:08:02 +11:00
parent fbeafe3ba7
commit b6b2951db7
18 changed files with 485 additions and 232 deletions

View File

@ -32,14 +32,15 @@ F_CPU = 16000000L
##############################################################################
ARCH = avr-
OPTIMIZE = -Os
CFLAGS = -g -Wall -Wstrict-prototypes $(OPTIMIZE) -mmcu=$(MCU_TARGET) -DF_CPU=$(F_CPU) $(DEFS) -std=gnu99 -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -ffunction-sections -save-temps
LDFLAGS = -Wl,--as-needed -Wl,--gc-sections -finline-functions-called-once
OPTIMIZE = -Os -ffunction-sections -finline-functions-called-once
# 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
CC = $(ARCH)gcc
OBJDUMP = $(ARCH)objdump
OBJCOPY = $(ARCH)objcopy
AVRDUDE = avrdude -F
AVRDUDE = avrdude
PROGPORT = /dev/arduino
PROGBAUD = 19200

View File

@ -13,14 +13,16 @@
#define _READ(IO) (IO ## _RPORT & MASK(IO ## _PIN))
#define _WRITE(IO, v) if (v) { IO ## _WPORT |= MASK(IO ## _PIN); } else { IO ## _WPORT &= ~MASK(IO ## _PIN); }
#define _TOGGLE(IO) (IO ## _RPORT = MASK(IO ## _PIN))
#define _SET_INPUT(IO) (IO ## _DDR |= MASK(IO ## _PIN))
#define _SET_OUTPUT(IO) (IO ## _DDR &= ~MASK(IO ## _PIN))
#define _SET_INPUT(IO) (IO ## _DDR &= ~MASK(IO ## _PIN))
#define _SET_OUTPUT(IO) (IO ## _DDR |= MASK(IO ## _PIN))
// why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
#define READ(IO) _READ(IO)
#define WRITE(IO, v) _WRITE(IO, v)
#define TOGGLE(IO) _TOGGLE(IO)
#define SET_INPUT(IO) _SET_INPUT(IO)
#define SET_OUTPUT(IO) _SET_OUTPUT(IO)

View File

@ -21,17 +21,21 @@ volatile uint8_t clock_flag_250ms = 0;
void clock_setup() {
// use system clock
ASSR = 0;
// no compare match, CTC mode
TCCR2A = MASK(WGM21);
// 128 prescaler (16MHz / 128 = 125KHz)
TCCR2B = MASK(CS22) | MASK(CS20);
// 125KHz / 125 = 1KHz for a 1ms tick rate
OCR2A = 125;
// interrupt on overflow, when counter reaches OCR2A
TIMSK2 |= MASK(TOIE2);
TIMSK2 |= MASK(OCIE2A);
}
ISR(TIMER2_OVF_vect) {
ISR(TIMER2_COMPA_vect) {
// global clock
clock++;

View File

@ -9,5 +9,6 @@ uint32_t clock_read(void);
extern volatile uint8_t clock_flag_250ms;
#define CLOCK_FLAG_250MS_TEMPCHECK 1
#define CLOCK_FLAG_250MS_REPORT 2
#endif /* _CLOCK_H */

View File

@ -3,6 +3,16 @@
#include <string.h>
#include "timer.h"
#include "serial.h"
#include "sermsg.h"
#ifndef ABS
#define ABS(v) (((v) >= 0)?(v):(-(v)))
#endif
#ifndef ABSDELTA
#define ABSDELTA(a, b) (((a) >= (b))?((a) - (b)):((b) - (a)))
#endif
/*
move queue
@ -16,8 +26,8 @@ DDA movebuffer[MOVEBUFFER_SIZE];
position tracking
*/
TARGET startpoint = { 0, 0, 0, 0, 0 };
TARGET current_position = { 0, 0, 0, 0, 0 };
TARGET startpoint = { 0, 0, 0, 0, FEEDRATE_SLOW_Z };
TARGET current_position = { 0, 0, 0, 0, FEEDRATE_SLOW_Z };
uint8_t queue_full() {
if (mb_tail == 0)
@ -26,6 +36,10 @@ uint8_t queue_full() {
return mb_head == (mb_tail - 1);
}
uint8_t queue_empty() {
return (mb_tail == mb_head) && !movebuffer[mb_tail].live;
}
void enqueue(TARGET *t) {
while (queue_full())
delay(WAITING_DELAY);
@ -43,6 +57,7 @@ void next_move() {
// queue is empty
disable_steppers();
setTimer(DEFAULT_TICK);
disableTimerInterrupt();
}
else {
uint8_t t = mb_tail;
@ -122,6 +137,12 @@ uint32_t approx_distance_3( int32_t dx, int32_t dy, int32_t dz )
return (( approx + 512 ) >> 10 );
}
uint32_t abs32(int32_t v) {
if (v < 0)
return -v;
return v;
}
/*
CREATE
*/
@ -129,18 +150,14 @@ uint32_t approx_distance_3( int32_t dx, int32_t dy, int32_t dz )
void dda_create(TARGET *target, DDA *dda) {
uint32_t distance;
// we start at the previous endpoint
// memcpy(&dda->currentpoint, &startpoint, sizeof(TARGET));
// we end at the passed command's endpoint
// we end at the passed target
memcpy(&dda->endpoint, target, sizeof(TARGET));
dda->x_delta = dda->endpoint.X - startpoint.X;
dda->y_delta = dda->endpoint.Y - startpoint.Y;
dda->z_delta = dda->endpoint.Z - startpoint.Z;
// always relative
dda->e_delta = dda->endpoint.E;
// always absolute
dda->f_delta = dda->endpoint.F - startpoint.F;
dda->x_delta = abs32(dda->endpoint.X - startpoint.X);
dda->y_delta = abs32(dda->endpoint.Y - startpoint.Y);
dda->z_delta = abs32(dda->endpoint.Z - startpoint.Z);
dda->e_delta = abs32(dda->endpoint.E - startpoint.E);
dda->f_delta = abs32(dda->endpoint.F - startpoint.F);
// since it's unusual to combine X, Y and Z changes in a single move on reprap, check if we can use simpler approximations before trying the full 3d approximation.
if (dda->z_delta == 0)
@ -163,22 +180,27 @@ void dda_create(TARGET *target, DDA *dda) {
if (dda->e_delta > dda->total_steps)
dda->total_steps = dda->e_delta;
if (dda->f_delta > dda->total_steps)
dda->total_steps = dda->f_delta;
if (dda->total_steps == 0)
if (dda->total_steps == 0) {
dda->nullmove = 1;
// copy F in case we're doing a null move speed change
startpoint.F = dda->endpoint.F;
current_position.F = dda->endpoint.F;
}
if (dda->f_delta > dda->total_steps) {
dda->f_scale = dda->f_delta / dda->total_steps;
if (dda->f_scale > 3) {
dda->f_delta /= dda->f_scale;
dda->f_delta = dda->total_steps;
}
else {
dda->f_scale = 1;
dda->total_steps = dda->f_delta;
}
}
else {
dda->f_scale = 1;
}
dda->x_direction = (dda->endpoint.X > startpoint.X)?1:0;
dda->y_direction = (dda->endpoint.Y > startpoint.Y)?1:0;
@ -200,6 +222,9 @@ void dda_create(TARGET *target, DDA *dda) {
// make sure we're not running
dda->live = 0;
// fire up
enableTimerInterrupt();
}
/*
@ -226,14 +251,23 @@ void dda_start(DDA *dda) {
*/
uint8_t can_step(uint8_t min, uint8_t max, int32_t current, int32_t target, uint8_t dir) {
if (target == current)
if (current == target)
return 0;
if (min && !dir)
return 0;
if (max && dir)
return 0;
if (dir) {
// forwards/positive
if (max)
return 0;
if (current > target)
return 0;
}
else {
// backwards/negative
if (min)
return 0;
if (target > current)
return 0;
}
return 255;
}
@ -251,10 +285,15 @@ void dda_step(DDA *dda) {
#define F_CAN_STEP 16
#define REAL_MOVE 32
WRITE(SCK, 1);
do {
step_option |= can_step(x_min(), x_max(), current_position.X, dda->endpoint.X, dda->x_direction) & X_CAN_STEP;
step_option |= can_step(y_min(), y_max(), current_position.Y, dda->endpoint.Y, dda->y_direction) & Y_CAN_STEP;
step_option |= can_step(z_min(), z_max(), current_position.Z, dda->endpoint.Z, dda->z_direction) & Z_CAN_STEP;
// step_option |= can_step(x_min(), x_max(), current_position.X, dda->endpoint.X, dda->x_direction) & X_CAN_STEP;
// step_option |= can_step(y_min(), y_max(), current_position.Y, dda->endpoint.Y, dda->y_direction) & Y_CAN_STEP;
// step_option |= can_step(z_min(), z_max(), current_position.Z, dda->endpoint.Z, dda->z_direction) & Z_CAN_STEP;
step_option |= can_step(0 , 0 , current_position.X, dda->endpoint.X, dda->x_direction) & X_CAN_STEP;
step_option |= can_step(0 , 0 , current_position.Y, dda->endpoint.Y, dda->y_direction) & Y_CAN_STEP;
step_option |= can_step(0 , 0 , current_position.Z, dda->endpoint.Z, dda->z_direction) & Z_CAN_STEP;
step_option |= can_step(0 , 0 , current_position.E, dda->endpoint.E, dda->e_direction) & E_CAN_STEP;
step_option |= can_step(0 , 0 , current_position.F, dda->endpoint.F, dda->f_direction) & F_CAN_STEP;
@ -264,13 +303,12 @@ void dda_step(DDA *dda) {
step_option |= REAL_MOVE;
x_step();
dda->x_counter += dda->total_steps;
if (dda->x_direction)
current_position.X++;
else
current_position.X--;
dda->x_counter += dda->total_steps;
}
}
@ -280,13 +318,12 @@ void dda_step(DDA *dda) {
step_option |= REAL_MOVE;
y_step();
dda->y_counter += dda->total_steps;
if (dda->y_direction)
current_position.Y++;
else
current_position.Y--;
dda->y_counter += dda->total_steps;
}
}
@ -296,13 +333,12 @@ void dda_step(DDA *dda) {
step_option |= REAL_MOVE;
z_step();
dda->z_counter += dda->total_steps;
if (dda->z_direction)
current_position.Z++;
else
current_position.Z--;
dda->z_counter += dda->total_steps;
}
}
@ -312,13 +348,12 @@ void dda_step(DDA *dda) {
step_option |= REAL_MOVE;
e_step();
dda->e_counter += dda->total_steps;
if (dda->e_direction)
current_position.E++;
else
current_position.E--;
dda->e_counter += dda->total_steps;
}
}
@ -328,13 +363,32 @@ void dda_step(DDA *dda) {
dda->f_counter += dda->total_steps;
if (dda->f_direction)
if (dda->f_scale == 0)
dda->f_scale = 1;
if (dda->f_direction) {
current_position.F += dda->f_scale;
else
if (current_position.F > dda->endpoint.F)
current_position.F = dda->endpoint.F;
}
else {
current_position.F -= dda->f_scale;
if (current_position.F < dda->endpoint.F)
current_position.F = dda->endpoint.F;
}
}
}
} while ( ((step_option & REAL_MOVE ) == 0) &&
serial_writechar('[');
serwrite_uint16(dda->f_scale);
serial_writechar(',');
serwrite_int32(current_position.F);
serial_writechar('/');
serwrite_int32(dda->endpoint.F);
serial_writechar('#');
serwrite_uint32(dda->move_duration);
serial_writechar(']');
} while ( ((step_option & REAL_MOVE ) == 0) &&
((step_option & F_CAN_STEP) != 0) );
// turn off step outputs, hopefully they've been on long enough by now to register with the drivers
@ -346,4 +400,6 @@ void dda_step(DDA *dda) {
// if we could step, we're still running
dda->live = (step_option & (X_CAN_STEP | Y_CAN_STEP | Z_CAN_STEP | E_CAN_STEP | F_CAN_STEP));
WRITE(SCK, 0);
}

View File

@ -26,11 +26,11 @@ typedef struct {
uint8_t nullmove :1;
uint8_t live :1;
int16_t x_delta;
int16_t y_delta;
int16_t z_delta;
int16_t e_delta;
int16_t f_delta;
uint32_t x_delta;
uint32_t y_delta;
uint32_t z_delta;
uint32_t e_delta;
uint32_t f_delta;
int32_t x_counter;
int32_t y_counter;
@ -51,7 +51,7 @@ extern TARGET startpoint;
extern TARGET current_position;
uint8_t queue_full(void);
inline uint8_t queue_empty(void) { return (mb_tail == mb_head) && !movebuffer[mb_tail].live; }
uint8_t queue_empty(void);
void enqueue(TARGET *t);
void next_move(void);

View File

@ -14,13 +14,15 @@ decfloat read_digit;
#define PI 3.1415926535
const char alphabet[] = "GMXYZEFSP";
/*
utility functions
*/
int8_t indexof(uint8_t c, char *string) {
int8_t indexof(uint8_t c, const char *string) {
int8_t i;
for (i = 0;string[i];i++) {
for (i = 0; string[i]; i++) {
if (c == string[i])
return i;
}
@ -29,7 +31,11 @@ int8_t indexof(uint8_t c, char *string) {
int32_t decfloat_to_int(decfloat *df, int32_t multiplicand, int32_t denominator) {
int32_t r = df->mantissa;
uint8_t e = df->exponent - 1;
uint8_t e = df->exponent;
// e=1 means we've seen a decimal point but no digits after it, and e=2 means we've seen a decimal point with one digit so it's too high by one if not zero
if (e)
e--;
// scale factors
if (multiplicand != 1)
@ -87,37 +93,44 @@ void SpecialMoveE(int32_t e, uint32_t f) {
void scan_char(uint8_t c) {
static uint8_t last_field = 0;
static GCODE_COMMAND next_target = { 0, 0, 0, 0, { 0, 0, 0, 0, 0 } };
static GCODE_COMMAND next_target = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, { 0, 0, 0, 0, 0 } };
// uppercase
if (c >= 'a' && c <= 'z')
c &= ~32;
// process field
if (indexof(c, "GMXYZEFSP\n") >= 0) {
if (last_field) {
if (last_field) {
if ((indexof(c, alphabet) >= 0) || (c == 10)) {
switch (last_field) {
case 'G':
next_target.G = read_digit.mantissa;
serwrite_uint8(next_target.G);
break;
case 'M':
next_target.M = read_digit.mantissa;
serwrite_uint8(next_target.M);
break;
case 'X':
next_target.target.X = decfloat_to_int(&read_digit, STEPS_PER_MM_X, 1);
serwrite_int32(next_target.target.X);
break;
case 'Y':
next_target.target.Y = decfloat_to_int(&read_digit, STEPS_PER_MM_Y, 1);
serwrite_int32(next_target.target.Y);
break;
case 'Z':
next_target.target.Z = decfloat_to_int(&read_digit, STEPS_PER_MM_Z, 1);
serwrite_int32(next_target.target.Z);
break;
case 'E':
next_target.target.E = decfloat_to_int(&read_digit, STEPS_PER_MM_E, 1);
serwrite_uint32(next_target.target.E);
break;
case 'F':
// just save an integer value for F, we need move distance and n_steps to convert it to a useful value, so wait until we have those to convert it
next_target.target.F = read_digit.mantissa;
serwrite_uint32(next_target.target.F);
break;
case 'S':
// if this is temperature, multiply by 4 to convert to quarter-degree units
@ -127,6 +140,7 @@ void scan_char(uint8_t c) {
next_target.S = decfloat_to_int(&read_digit, 4, 1);
else
next_target.S = decfloat_to_int(&read_digit, 1, 1);
serwrite_uint16(next_target.S);
break;
case 'P':
// if this is dwell, multiply by 1 million to convert seconds to milliseconds
@ -134,66 +148,103 @@ 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);
serwrite_uint16(next_target.P);
break;
}
last_field = 0;
read_digit.sign = 0;
read_digit.mantissa = 0;
read_digit.exponent = 0;
}
last_field = c;
}
// not in a comment?
if ((option_bitfield & OPTION_COMMENT) == 0) {
if (indexof(c, alphabet) >= 0) {
last_field = c;
serial_writechar(c);
}
// process character
switch (c) {
// each command is either G or M, so preserve previous G/M unless a new one has appeared
case 'G':
next_target.seen |= SEEN_G;
next_target.seen_G = 1;
next_target.seen_M = 0;
next_target.M = 0;
break;
case 'M':
next_target.seen |= SEEN_M;
next_target.seen_M = 1;
next_target.seen_G = 0;
next_target.G = 0;
break;
case 'X':
next_target.seen |= SEEN_X;
next_target.seen_X = 1;
break;
case 'Y':
next_target.seen |= SEEN_Y;
next_target.seen_Y = 1;
break;
case 'Z':
next_target.seen |= SEEN_Z;
next_target.seen_Z = 1;
break;
case 'E':
next_target.seen |= SEEN_E;
next_target.seen_E = 1;
break;
case 'F':
next_target.seen |= SEEN_F;
next_target.seen_F = 1;
break;
case 'S':
next_target.seen |= SEEN_S;
next_target.seen_S = 1;
break;
case 'P':
next_target.seen |= SEEN_P;
next_target.seen_P = 1;
break;
case '\n':
// process
process_gcode_command(&next_target);
// save options
option_bitfield = next_target.option;
// reset variables
last_field = 0;
next_target.seen = 0;
serial_writeblock((uint8_t *) "OK\n", 3);
// comments
case ';':
option_bitfield |= OPTION_COMMENT;
break;
// now for some numeracy
case '-':
read_digit.sign = 1;
// force sign to be at start of number
read_digit.exponent = 0;
read_digit.mantissa = 0;
break;
case '.':
if (read_digit.exponent == 0)
read_digit.exponent = 1;
break;
default:
// can't do ranges in switch..case, so process actual digits here
if (c >= '0' && c <= '9') {
read_digit.mantissa = (read_digit.mantissa << 3) + (read_digit.mantissa << 1) + (c - '0');
if (read_digit.exponent)
read_digit.exponent++;
}
}
}
// process digits
else if (c == '-')
read_digit.sign = 1;
else if ((c == '.') && (read_digit.exponent == 0))
read_digit.exponent = 1;
else if (c >= '0' && c <= '9') {
read_digit.mantissa = (read_digit.mantissa << 3) + (read_digit.mantissa << 1) + (c - '0');
if (read_digit.exponent)
read_digit.exponent++;
// got a command
if (c == 10) {
serial_writechar(c);
// process
process_gcode_command(&next_target);
// save options
option_bitfield = next_target.option;
option_bitfield &= ~OPTION_COMMENT;
// reset variables
last_field = 0;
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;
read_digit.sign = 0;
read_digit.mantissa = 0;
read_digit.exponent = 0;
serial_writestr_P(PSTR("OK\n"));
}
}
@ -205,7 +256,7 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
gcmd->target.E += startpoint.E;
}
if (gcmd->seen & SEEN_G) {
if (gcmd->seen_G) {
switch (gcmd->G) {
// G0 - rapid, unsynchronised motion
// since it would be a major hassle to force the dda to not synchronise, just provide a fast feedrate and hope it's close enough to what host expects
@ -306,12 +357,12 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
// TODO: spit an error
default:
serial_writeblock((uint8_t *) "E: Bad G-code ", 14);
serial_writestr_P(PSTR("E: Bad G-code "));
serwrite_uint8(gcmd->G);
serial_writechar('\n');
}
}
if (gcmd->seen & SEEN_M) {
if (gcmd->seen_M) {
switch (gcmd->M) {
// M101- extruder on
case 101:
@ -335,7 +386,7 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
// do .. while block here to provide local scope for temp
do {
uint16_t t = temp_get();
serial_writeblock((uint8_t *) "T: ", 3);
serial_writestr_P(PSTR("T: "));
serwrite_uint16(t >> 2);
serial_writechar('.');
if (t & 3) {
@ -366,7 +417,7 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
// TODO: spit an error
default:
serial_writeblock((uint8_t *) "E: Bad M-code ", 14);
serial_writestr_P(PSTR("E: Bad M-code "));
serwrite_uint8(gcmd->M);
serial_writechar('\n');
}

View File

@ -12,21 +12,21 @@ typedef struct {
} decfloat;
typedef struct {
uint16_t seen;
#define SEEN_G 1
#define SEEN_M 2
#define SEEN_X 4
#define SEEN_Y 8
#define SEEN_Z 16
#define SEEN_E 32
#define SEEN_F 64
#define SEEN_S 128
#define SEEN_P 256
uint8_t seen_G :1;
uint8_t seen_M :1;
uint8_t seen_X :1;
uint8_t seen_Y :1;
uint8_t seen_Z :1;
uint8_t seen_E :1;
uint8_t seen_F :1;
uint8_t seen_S :1;
uint8_t seen_P :1;
uint8_t option;
#define OPTION_RELATIVE 1
#define OPTION_SYNCHRONISE 2
#define OPTION_UNIT_INCHES 4
#define OPTION_COMMENT 128
uint8_t G;
uint8_t M;
@ -36,7 +36,7 @@ typedef struct {
uint16_t P;
} GCODE_COMMAND;
int8_t indexof(uint8_t c, char *string);
int8_t indexof(uint8_t c, const char *string);
int32_t decfloat_to_int(decfloat *df, int32_t multiplicand, int32_t denominator);
void scan_char(uint8_t c);

View File

@ -13,9 +13,12 @@
#include "timer.h"
#include "clock.h"
#include "temp.h"
#include "sermsg.h"
int main (void)
{
uint8_t report;
// set up serial
serial_init();
@ -45,26 +48,89 @@ int main (void)
WRITE(MISO, 1); SET_INPUT(MISO);
WRITE(SS, 0); SET_OUTPUT(SS);
// set up timers
setupTimerInterrupt();
// set up clock
clock_setup();
// enable interrupts
sei();
serial_writeblock((uint8_t *) "Start\n", 6);
// say hi to host
serial_writestr_P(PSTR("Start\n"));
// start queue
//enableTimerInterrupt();
// main loop
for (;;)
{
if (serial_rxchars()) {
uint8_t c = serial_popchar();
// TOGGLE(SCK);
scan_char(c);
}
if (clock_flag_250ms & CLOCK_FLAG_250MS_TEMPCHECK) {
clock_flag_250ms &= ~CLOCK_FLAG_250MS_TEMPCHECK;
temp_tick();
// if (clock_flag_250ms & CLOCK_FLAG_250MS_TEMPCHECK) {
// clock_flag_250ms &= ~CLOCK_FLAG_250MS_TEMPCHECK;
// temp_tick();
// }
if (clock_flag_250ms & CLOCK_FLAG_250MS_REPORT) {
clock_flag_250ms &= ~CLOCK_FLAG_250MS_REPORT;
report++;
if (report == 4) {
report = 0;
// current move
serial_writestr_P(PSTR("DDA: f#"));
serwrite_int32(movebuffer[mb_head].f_counter);
serial_writechar('/');
serwrite_uint16(movebuffer[mb_head].f_scale);
serial_writechar('/');
serwrite_int16(movebuffer[mb_head].f_delta);
serial_writechar('\n');
// current position
serial_writestr_P(PSTR("Pos: "));
serwrite_int32(current_position.X);
serial_writechar(',');
serwrite_int32(current_position.Y);
serial_writechar(',');
serwrite_int32(current_position.Z);
serial_writechar(',');
serwrite_uint32(current_position.E);
serial_writechar(',');
serwrite_uint32(current_position.F);
serial_writechar('\n');
// target position
serial_writestr_P(PSTR("Tar: "));
serwrite_int32(movebuffer[mb_head].endpoint.X);
serial_writechar(',');
serwrite_int32(movebuffer[mb_head].endpoint.Y);
serial_writechar(',');
serwrite_int32(movebuffer[mb_head].endpoint.Z);
serial_writechar(',');
serwrite_uint32(movebuffer[mb_head].endpoint.E);
serial_writechar(',');
serwrite_uint32(movebuffer[mb_head].endpoint.F);
serial_writechar('\n');
// Queue
serial_writestr_P(PSTR("Q : "));
// serwrite_uint8((mb_head - mb_tail) & (MOVEBUFFER_SIZE - 1));
serwrite_uint8(mb_head);
serial_writechar('/');
serwrite_uint8(mb_tail);
if (queue_full())
serial_writechar('F');
if (queue_empty())
serial_writechar('E');
serial_writechar('\n');
}
}
}
}

View File

@ -23,12 +23,12 @@
#define Y_DIR_PIN AIO4
#define Y_MIN_PIN AIO5
#define Z_STEP_PIN DIO5
#define Z_DIR_PIN DIO7
#define Z_MIN_PIN DIO8
#define Z_STEP_PIN DIO2
#define Z_DIR_PIN DIO3
#define Z_MIN_PIN DIO4
#define E_STEP_PIN DIO2
#define E_DIR_PIN DIO3
#define E_STEP_PIN DIO7
#define E_DIR_PIN DIO8
// list of PWM-able pins and corresponding timers
// OC0A DIO6
@ -41,7 +41,7 @@
#define HEATER_PIN DIO6
#define HEATER_PIN_PWM OC0A
#define FAN_PIN DIO9
#define FAN_PIN DIO5
#define SCK DIO13
#define MISO DIO12

View File

@ -1,26 +1,26 @@
#include "ringbuffer.h"
uint16_t _rb_mod(uint16_t num, uint16_t denom)
RB_BITS _rb_mod(RB_BITS num, RB_BITS denom)
{
for (; num >= denom; num -= denom);
return num;
}
void ringbuffer_init(ringbuffer *buf, int bufsize)
void ringbuffer_init(ringbuffer *buf, RB_BITS bufsize)
{
buf->read_pointer = 0;
buf->write_pointer = 0;
buf->size = bufsize - sizeof(ringbuffer);
}
uint16_t ringbuffer_canread(ringbuffer *buf)
RB_BITS ringbuffer_canread(ringbuffer *buf)
{
return _rb_mod(buf->write_pointer + buf->size + buf->size - buf->read_pointer, buf->size);
return _rb_mod(buf->size + buf->write_pointer - buf->read_pointer, buf->size);
}
uint16_t ringbuffer_canwrite(ringbuffer *buf)
RB_BITS ringbuffer_canwrite(ringbuffer *buf)
{
return _rb_mod(buf->read_pointer + buf->size + buf->size - buf->write_pointer - 1, buf->size);
return _rb_mod(buf->size + buf->size + buf->read_pointer - buf->write_pointer - 1, buf->size);
}
uint8_t ringbuffer_readchar(ringbuffer *buf)
@ -44,23 +44,23 @@ void ringbuffer_writechar(ringbuffer *buf, uint8_t data)
}
uint8_t ringbuffer_peekchar(ringbuffer *buf, uint16_t index)
uint8_t ringbuffer_peekchar(ringbuffer *buf, RB_BITS index)
{
return buf->data[_rb_mod(buf->read_pointer + index, buf->size)];
}
uint16_t ringbuffer_readblock(ringbuffer *buf, uint8_t *newbuf, int size)
RB_BITS ringbuffer_readblock(ringbuffer *buf, uint8_t *newbuf, RB_BITS size)
{
uint16_t nc, i;
RB_BITS nc, i;
uint8_t *rp, *ms;
if ((nc = ringbuffer_canread(buf)) < size)
size = nc;
if (size)
{
for (i = 0, rp = buf->data + buf->read_pointer, ms = buf->data + buf->size; i < size; i++, rp++)
for (i = 0, rp = ((uint8_t *) buf->data + buf->read_pointer), ms = ((uint8_t *) buf->data + buf->size); i < size; i++, rp++)
{
if (rp >= ms)
rp = buf->data;
rp = (uint8_t *) buf->data;
newbuf[i] = *rp;
}
buf->read_pointer = rp - buf->data;
@ -68,19 +68,19 @@ uint16_t ringbuffer_readblock(ringbuffer *buf, uint8_t *newbuf, int size)
return size;
}
uint16_t ringbuffer_writeblock(ringbuffer *buf, uint8_t *data, int size)
RB_BITS ringbuffer_writeblock(ringbuffer *buf, uint8_t *data, RB_BITS size)
{
uint16_t nc, i;
RB_BITS nc, i;
uint8_t *wp, *ms;
if ((nc = ringbuffer_canwrite(buf)) < size)
size = nc;
if (size)
{
for (i = 0, wp = buf->write_pointer + buf->data, ms = buf->data + buf->size; i < size; i++, wp++)
for (i = 0, wp = (uint8_t *) (buf->write_pointer + buf->data), ms = (uint8_t *) (buf->data + buf->size); i < size; i++, wp++)
{
if (wp >= ms)
wp = buf->data;
wp = (uint8_t *) buf->data;
*wp = data[i];
}
buf->write_pointer = wp - buf->data;

View File

@ -4,23 +4,25 @@
#include <stdint.h>
#include <avr/interrupt.h>
#define RB_BITS uint8_t
typedef struct {
uint16_t read_pointer;
uint16_t write_pointer;
uint16_t size;
uint8_t data[];
volatile RB_BITS read_pointer;
volatile RB_BITS write_pointer;
volatile RB_BITS size;
volatile RB_BITS data[];
} ringbuffer;
void ringbuffer_init(ringbuffer *buf, int bufsize);
void ringbuffer_init(ringbuffer *buf, RB_BITS bufsize);
uint16_t ringbuffer_canread(ringbuffer *buf);
uint16_t ringbuffer_canwrite(ringbuffer *buf);
RB_BITS ringbuffer_canread(ringbuffer *buf);
RB_BITS ringbuffer_canwrite(ringbuffer *buf);
uint8_t ringbuffer_readchar(ringbuffer *buf);
uint8_t ringbuffer_peekchar(ringbuffer *buf, uint16_t index);
uint16_t ringbuffer_readblock(ringbuffer *buf, uint8_t *newbuf, int size);
uint8_t ringbuffer_peekchar(ringbuffer *buf, RB_BITS index);
RB_BITS ringbuffer_readblock(ringbuffer *buf, uint8_t *newbuf, RB_BITS size);
void ringbuffer_writechar(ringbuffer *buf, uint8_t data);
uint16_t ringbuffer_writeblock(ringbuffer *buf, uint8_t *data, int size);
RB_BITS ringbuffer_writeblock(ringbuffer *buf, uint8_t *data, RB_BITS size);
#endif /* _RINGBUFFER_H */

View File

@ -8,6 +8,9 @@
volatile uint8_t _rx_buffer[BUFSIZE];
volatile uint8_t _tx_buffer[BUFSIZE];
#define rx_buffer ((ringbuffer *) _rx_buffer)
#define tx_buffer ((ringbuffer *) _tx_buffer)
void serial_init()
{
ringbuffer_init(rx_buffer, BUFSIZE);
@ -30,13 +33,9 @@ ISR(USART_RX_vect)
ISR(USART_UDRE_vect)
{
if (ringbuffer_canread(tx_buffer))
{
UDR0 = ringbuffer_readchar(tx_buffer);
}
else
{
UCSR0B &= ~(1 << UDRIE0);
}
}
uint16_t serial_rxchars()
@ -61,12 +60,34 @@ uint16_t serial_recvblock(uint8_t *block, int blocksize)
void serial_writechar(uint8_t data)
{
for (;ringbuffer_canwrite(tx_buffer) == 0;);
ringbuffer_writechar(tx_buffer, data);
UCSR0B |= (1 << UDRIE0);
}
void serial_writeblock(uint8_t *data, int datalen)
void serial_writeblock(void *data, int datalen)
{
ringbuffer_writeblock(tx_buffer, data, datalen);
for (int i = 0; i < datalen; i++)
serial_writechar(((uint8_t *) data)[i]);
}
void serial_writechar_P(PGM_P data)
{
for (;ringbuffer_canwrite(tx_buffer) == 0;);
ringbuffer_writechar(tx_buffer, pgm_read_byte(data));
UCSR0B |= (1 << UDRIE0);
}
void serial_writeblock_P(PGM_P data, int datalen)
{
for (int i = 0; i < datalen; i++)
serial_writechar_P(&data[i]);
}
void serial_writestr_P(PGM_P data)
{
uint8_t i = 0;
// yes, this is *supposed* to be assignment rather than comparison
for (uint8_t r; (r = pgm_read_byte(&data[i])); i++)
serial_writechar(r);
}

View File

@ -3,14 +3,7 @@
#include <stdint.h>
#include <avr/io.h>
#include "ringbuffer.h"
#define rx_buffer ((ringbuffer *) _rx_buffer)
#define tx_buffer ((ringbuffer *) _tx_buffer)
extern volatile uint8_t _rx_buffer[];
extern volatile uint8_t _tx_buffer[];
#include <avr/pgmspace.h>
void serial_init(void);
@ -21,6 +14,11 @@ uint8_t serial_popchar(void);
void serial_writechar(uint8_t data);
uint16_t serial_recvblock(uint8_t *block, int blocksize);
void serial_writeblock(uint8_t *data, int datalen);
void serial_writeblock(void *data, int datalen);
void serial_writechar_P(PGM_P data);
void serial_writeblock_P(PGM_P data, int datalen);
void serial_writestr_P(PGM_P data);
#endif /* _SERIAL_H */

View File

@ -2,42 +2,105 @@
#include "serial.h"
void serwrite_uint8(uint8_t v) {
uint8_t t;
if (v > 100) {
// void serwrite_uint8(uint8_t v) {
// serwrite_uint32(v);
// }
//
// void serwrite_int8(int8_t v) {
// if (v < 0) {
// serial_writechar('-');
// v = -v;
// }
//
// serwrite_uint32(v);
// }
//
// void serwrite_uint16(uint16_t v) {
// serwrite_uint32(v);
// }
//
// void serwrite_int16(int16_t v) {
// if (v < 0) {
// serial_writechar('-');
// v = -v;
// }
//
// serwrite_uint32(v);
// }
void serwrite_uint32(uint32_t v) {
uint8_t t = 0;
if (v >= 1000000000) {
for (t = 0; v >= 1000000000; v -= 1000000000, t++);
serial_writechar(t + '0');
}
if (v >= 100000000) {
for (t = 0; v >= 100000000; v -= 100000000, t++);
serial_writechar(t + '0');
}
else if (t != 0)
serial_writechar('0');
if (v >= 10000000) {
for (t = 0; v >= 10000000; v -= 10000000, t++);
serial_writechar(t + '0');
}
else if (t != 0)
serial_writechar('0');
if (v >= 1000000) {
for (t = 0; v >= 1000000; v -= 1000000, t++);
serial_writechar(t + '0');
}
else if (t != 0)
serial_writechar('0');
if (v >= 100000) {
for (t = 0; v >= 100000; v -= 100000, t++);
serial_writechar(t + '0');
}
else if (t != 0)
serial_writechar('0');
if (v >= 10000) {
for (t = 0; v >= 10000; v -= 10000, t++);
serial_writechar(t + '0');
}
else if (t != 0)
serial_writechar('0');
if (v >= 1000) {
for (t = 0; v >= 1000; v -= 1000, t++);
serial_writechar(t + '0');
}
else if (t != 0)
serial_writechar('0');
if (v >= 100) {
t = v / 100;
serial_writechar(t + '0');
v -= t;
v -= (t * 100);
}
if (v > 10) {
else if (t != 0)
serial_writechar('0');
if (v >= 10) {
t = v / 10;
serial_writechar(t + '0');
v -= t;
v -= (t * 10);
}
else if (t != 0)
serial_writechar('0');
serial_writechar(v + '0');
}
void serwrite_uint16(uint16_t v) {
uint16_t t;
if (v > 10000) {
t = v / 10000;
serial_writechar(t + '0');
v -= t;
void serwrite_int32(int32_t v) {
if (v < 0) {
serial_writechar('-');
v = -v;
}
if (v > 1000) {
t = v / 1000;
serial_writechar(t + '0');
v -= t;
}
if (v > 100) {
t = v / 100;
serial_writechar(t + '0');
v -= t;
}
if (v > 10) {
t = v / 10;
serial_writechar(t + '0');
v -= t;
}
serial_writechar(v + '0');
serwrite_uint32(v);
}

View File

@ -3,7 +3,18 @@
#include <stdint.h>
void serwrite_uint8(uint8_t v);
void serwrite_uint16(uint16_t v);
// void serwrite_uint8(uint8_t v);
// void serwrite_int8(int8_t v);
//
// void serwrite_uint16(uint16_t v);
// void serwrite_int16(int16_t v);
#define serwrite_uint8(v) serwrite_uint32(v)
#define serwrite_int8(v) serwrite_int32(v)
#define serwrite_uint16(v) serwrite_uint32(v)
#define serwrite_int16(v) serwrite_int32(v)
void serwrite_uint32(uint32_t v);
void serwrite_int32(int32_t v);
#endif /* _SERMSG_H */

View File

@ -6,16 +6,15 @@
#include "dda.h"
ISR(TIMER1_COMPA_vect) {
// static interruptBlink = 0;
//
// interruptBlink++;
// if (interruptBlink == 0x80) {
// blink();
// interruptBlink = 0;
// }
if(movebuffer[mb_tail].live) {
// this interrupt can be interruptible
disableTimerInterrupt();
sei();
if(movebuffer[mb_tail].live)
dda_step(&movebuffer[mb_tail]);
enableTimerInterrupt();
}
else
next_move();
}
@ -23,26 +22,16 @@ ISR(TIMER1_COMPA_vect) {
void setupTimerInterrupt()
{
//clear the registers
// no outputs
TCCR1A = 0;
TCCR1B = 0;
TCCR1C = 0;
// CTC mode
TCCR1B = MASK(WGM12);
// no interrupts yet
TIMSK1 = 0;
//waveform generation = 0100 = CTC
TCCR1B &= ~(1<<WGM13);
TCCR1B |= (1<<WGM12);
TCCR1A &= ~(1<<WGM11);
TCCR1A &= ~(1<<WGM10);
//output mode = 00 (disconnected)
TCCR1A &= ~(1<<COM1A1);
TCCR1A &= ~(1<<COM1A0);
TCCR1A &= ~(1<<COM1B1);
TCCR1A &= ~(1<<COM1B0);
//start off with a slow frequency.
setTimerResolution(4);
setTimerCeiling(65535);
setTimer(10000);
}
uint8_t getTimerResolution(const uint32_t delay)
@ -52,37 +41,32 @@ uint8_t getTimerResolution(const uint32_t delay)
// our slowest speed at our highest resolution ( (2^16-1) * 0.0625 usecs = 4095 usecs (4 millisecond max))
// range: 8Mhz max - 122hz min
if (delay <= 65535L)
return 0;
return 1;
// our slowest speed at our next highest resolution ( (2^16-1) * 0.5 usecs = 32767 usecs (32 millisecond max))
// range:1Mhz max - 15.26hz min
else if (delay <= 524280L)
return 1;
return 2;
// our slowest speed at our medium resolution ( (2^16-1) * 4 usecs = 262140 usecs (0.26 seconds max))
// range: 125Khz max - 1.9hz min
else if (delay <= 4194240L)
return 2;
return 3;
// our slowest speed at our medium-low resolution ( (2^16-1) * 16 usecs = 1048560 usecs (1.04 seconds max))
// range: 31.25Khz max - 0.475hz min
else if (delay <= 16776960L)
return 3;
return 4;
// our slowest speed at our lowest resolution ((2^16-1) * 64 usecs = 4194240 usecs (4.19 seconds max))
// range: 7.812Khz max - 0.119hz min
// else if (delay <= 67107840L)
// return 4;
// return 5;
//its really slow... hopefully we can just get by with super slow.
// else
return 4;
return 5;
}
void setTimerResolution(uint8_t r)
{
//here's how you figure out the tick size:
// 1000000 / ((F_CPU / prescaler))
// 1000000 = microseconds in 1 second
// prescaler = your prescaler
// assuming CS10,CS11,CS12 are adjacent bits in platform endian order,
TCCR1B = (TCCR1B & ~(MASK(CS10) | MASK(CS11) | MASK(CS12))) | ((r + 1) << CS10);
TCCR1B = (TCCR1B & ~(MASK(CS12) | MASK(CS11) | MASK(CS10))) | (r << CS10);
}
uint16_t getTimerCeiling(const uint32_t delay)

View File

@ -25,15 +25,8 @@ void delay_ms(uint32_t delay);
#define delay_us(d) delayMicrosecondsInterruptible(d)
void delayMicrosecondsInterruptible(unsigned int us);
inline void enableTimerInterrupt(void)
{
TIMSK1 |= (1<<OCIE1A);
}
inline void disableTimerInterrupt(void)
{
TIMSK1 &= ~(1<<OCIE1A);
}
#define enableTimerInterrupt() do { TIMSK1 |= (1<<OCIE1A); } while (0)
#define disableTimerInterrupt() do { TIMSK1 &= ~(1<<OCIE1A); } while (0)
#define setTimerCeiling(c) OCR1A = c