time to save, added a tiny printf implementation which actually gives less code than printing everything out manually, waiting for temperature is now queueable so subsequent moves can be buffered ahead of time, and a debug flags system for dynamic enable/disable of debug. btw, atmega168 doesn't have enough space for debug so turn it off if you have one.

This commit is contained in:
Michael Moon 2010-03-17 04:11:33 +11:00
parent 06cdfaa251
commit bce08901d8
19 changed files with 574 additions and 245 deletions

View File

@ -14,7 +14,7 @@
PROGRAM = mendel PROGRAM = mendel
SOURCES = $(PROGRAM).c serial.c dda.c gcode.c timer.c clock.c temp.c sermsg.c dda_queue.c watchdog.c SOURCES = $(PROGRAM).c serial.c dda.c gcode.c timer.c clock.c temp.c sermsg.c dda_queue.c watchdog.c debug.c sersendf.c
############################################################################## ##############################################################################
# # # #
@ -41,7 +41,7 @@ DEFS = -DF_CPU=$(F_CPU)
# DEFS += "-DREQUIRE_LINENUMBER" # DEFS += "-DREQUIRE_LINENUMBER"
# DEFS += "-DREQUIRE_CHECKSUM" # DEFS += "-DREQUIRE_CHECKSUM"
OPTIMIZE = -Os -ffunction-sections -finline-functions-called-once -DDEBUG=0 OPTIMIZE = -Os -ffunction-sections -finline-functions-called-once -DDEBUG
# OPTIMIZE = -O0 # OPTIMIZE = -O0
CFLAGS = -g -Wall -Wstrict-prototypes $(OPTIMIZE) -mmcu=$(MCU_TARGET) $(DEFS) -std=gnu99 -funsigned-char -funsigned-bitfields -fpack-struct -fshort-enums -save-temps CFLAGS = -g -Wall -Wstrict-prototypes $(OPTIMIZE) -mmcu=$(MCU_TARGET) $(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

@ -7,6 +7,8 @@
#include "serial.h" #include "serial.h"
#include "sermsg.h" #include "sermsg.h"
#include "dda_queue.h" #include "dda_queue.h"
#include "debug.h"
#include "sersendf.h"
#ifndef ABS #ifndef ABS
#define ABS(v) (((v) >= 0)?(v):(-(v))) #define ABS(v) (((v) >= 0)?(v):(-(v)))
@ -16,10 +18,6 @@
#define ABSDELTA(a, b) (((a) >= (b))?((a) - (b)):((b) - (a))) #define ABSDELTA(a, b) (((a) >= (b))?((a) - (b)):((b) - (a)))
#endif #endif
#ifndef DEBUG
#define DEBUG 0
#endif
/* /*
step timeout step timeout
*/ */
@ -30,8 +28,8 @@ uint8_t steptimeout = 0;
position tracking position tracking
*/ */
TARGET startpoint = { 0, 0, 0, 0, 0 }; TARGET startpoint __attribute__ ((__section__ (".bss")));
TARGET current_position = { 0, 0, 0, 0, 0 }; TARGET current_position __attribute__ ((__section__ (".bss")));
/* /*
utility functions utility functions
@ -129,8 +127,9 @@ void dda_create(DDA *dda, TARGET *target) {
// initialise DDA to a known state // initialise DDA to a known state
dda->live = 0; dda->live = 0;
dda->total_steps = 0; dda->total_steps = 0;
dda->waitfor_temp = 0;
if (1) if (debug_flags & DEBUG_DDA)
serial_writestr_P(PSTR("\n{DDA_CREATE: [")); serial_writestr_P(PSTR("\n{DDA_CREATE: ["));
// we end at the passed target // we end at the passed target
@ -146,7 +145,7 @@ void dda_create(DDA *dda, TARGET *target) {
dda->z_direction = (target->Z >= startpoint.Z)?1:0; dda->z_direction = (target->Z >= startpoint.Z)?1:0;
dda->e_direction = (target->E >= startpoint.E)?1:0; dda->e_direction = (target->E >= startpoint.E)?1:0;
if (1) { if (debug_flags & DEBUG_DDA) {
if (dda->x_direction == 0) if (dda->x_direction == 0)
serial_writechar('-'); serial_writechar('-');
serwrite_uint32(dda->x_delta); serial_writechar(','); serwrite_uint32(dda->x_delta); serial_writechar(',');
@ -172,7 +171,7 @@ void dda_create(DDA *dda, TARGET *target) {
if (dda->e_delta > dda->total_steps) if (dda->e_delta > dda->total_steps)
dda->total_steps = dda->e_delta; dda->total_steps = dda->e_delta;
if (1) { if (debug_flags & DEBUG_DDA) {
serial_writestr_P(PSTR("ts:")); serwrite_uint32(dda->total_steps); serial_writestr_P(PSTR("ts:")); serwrite_uint32(dda->total_steps);
} }
@ -198,7 +197,7 @@ void dda_create(DDA *dda, TARGET *target) {
if (distance < 2) if (distance < 2)
distance = dda->e_delta * UM_PER_STEP_E; distance = dda->e_delta * UM_PER_STEP_E;
if (1) { if (debug_flags & DEBUG_DDA) {
serial_writestr_P(PSTR(",ds:")); serwrite_uint32(distance); serial_writestr_P(PSTR(",ds:")); serwrite_uint32(distance);
} }
@ -222,7 +221,7 @@ void dda_create(DDA *dda, TARGET *target) {
// c is initial step time in IOclk ticks // c is initial step time in IOclk ticks
dda->c = (move_duration / startpoint.F) << 8; dda->c = (move_duration / startpoint.F) << 8;
if (1) { if (debug_flags & DEBUG_DDA) {
serial_writestr_P(PSTR(",md:")); serwrite_uint32(move_duration); serial_writestr_P(PSTR(",md:")); serwrite_uint32(move_duration);
serial_writestr_P(PSTR(",c:")); serwrite_uint32(dda->c >> 8); serial_writestr_P(PSTR(",c:")); serwrite_uint32(dda->c >> 8);
} }
@ -245,30 +244,34 @@ void dda_create(DDA *dda, TARGET *target) {
// we'll have to do it a few different ways depending on the msb locations of each // we'll have to do it a few different ways depending on the msb locations of each
if ((msb_tot + msb_ssq) <= 30) { if ((msb_tot + msb_ssq) <= 30) {
// we have room to do all the multiplies first // we have room to do all the multiplies first
serial_writechar('A'); if (debug_flags & DEBUG_DDA)
serial_writechar('A');
dda->n = ((int32_t) (dda->total_steps * ssq) / dsq) + 1; dda->n = ((int32_t) (dda->total_steps * ssq) / dsq) + 1;
} }
else if (msb_tot >= msb_ssq) { else if (msb_tot >= msb_ssq) {
// total steps has more precision // total steps has more precision
serial_writechar('B'); if (debug_flags & DEBUG_DDA)
serial_writechar('B');
dda->n = (((int32_t) dda->total_steps / dsq) * (int32_t) ssq) + 1; dda->n = (((int32_t) dda->total_steps / dsq) * (int32_t) ssq) + 1;
} }
else { else {
// otherwise // otherwise
serial_writechar('C'); if (debug_flags & DEBUG_DDA)
serial_writechar('C');
dda->n = (((int32_t) ssq / dsq) * (int32_t) dda->total_steps) + 1; dda->n = (((int32_t) ssq / dsq) * (int32_t) dda->total_steps) + 1;
} }
if (1) { if (debug_flags & DEBUG_DDA) {
serial_writestr_P(PSTR("\n{DDA:CA end_c:")); serwrite_uint32(dda->end_c >> 8); // serial_writestr_P(PSTR("\n{DDA:CA end_c:")); serwrite_uint32(dda->end_c >> 8);
serial_writestr_P(PSTR(", n:")); serwrite_int32(dda->n); // serial_writestr_P(PSTR(", n:")); serwrite_int32(dda->n);
serial_writestr_P(PSTR(", md:")); serwrite_uint32(move_duration); // serial_writestr_P(PSTR(", md:")); serwrite_uint32(move_duration);
serial_writestr_P(PSTR(", ssq:")); serwrite_uint32(ssq); // serial_writestr_P(PSTR(", ssq:")); serwrite_uint32(ssq);
serial_writestr_P(PSTR(", esq:")); serwrite_uint32(esq); // serial_writestr_P(PSTR(", esq:")); serwrite_uint32(esq);
serial_writestr_P(PSTR(", dsq:")); serwrite_int32(dsq); // serial_writestr_P(PSTR(", dsq:")); serwrite_int32(dsq);
serial_writestr_P(PSTR(", msbssq:")); serwrite_uint8(msb_ssq); // serial_writestr_P(PSTR(", msbssq:")); serwrite_uint8(msb_ssq);
serial_writestr_P(PSTR(", msbtot:")); serwrite_uint8(msb_tot); // serial_writestr_P(PSTR(", msbtot:")); serwrite_uint8(msb_tot);
serial_writestr_P(PSTR("}\n")); // serial_writestr_P(PSTR("}\n"));
sersendf_P(PSTR("\n{DDA:CA end_c:%lu, n:%ld, md:%lu, ssq:%lu, esq:%lu, dsq:%lu, msbssq:%u, msbtot:%u}\n"), dda->end_c >> 8, dda->n, move_duration, ssq, esq, dsq, msb_ssq, msb_tot);
} }
dda->accel = 1; dda->accel = 1;
@ -277,11 +280,13 @@ void dda_create(DDA *dda, TARGET *target) {
dda->accel = 0; dda->accel = 0;
} }
if (1) if (debug_flags & DEBUG_DDA)
serial_writestr_P(PSTR("] }\n")); serial_writestr_P(PSTR("] }\n"));
// next dda starts where we finish // next dda starts where we finish
memcpy(&startpoint, target, sizeof(TARGET)); memcpy(&startpoint, target, sizeof(TARGET));
// E is always relative, reset it here
startpoint.E = 0;
} }
/* /*
@ -293,21 +298,26 @@ void dda_start(DDA *dda) {
if (dda->nullmove) { if (dda->nullmove) {
// just change speed? // just change speed?
current_position.F = dda->endpoint.F; current_position.F = dda->endpoint.F;
return;
} }
else {
if (dda->waitfor_temp) {
serial_writestr_P(PSTR("Waiting for target temp\n"));
}
else {
// ensure steppers are ready to go
steptimeout = 0;
power_on();
// ensure steppers are ready to go // set direction outputs
steptimeout = 0; x_direction(dda->x_direction);
power_on(); y_direction(dda->y_direction);
z_direction(dda->z_direction);
e_direction(dda->e_direction);
}
// set direction outputs // ensure this dda starts
x_direction(dda->x_direction); dda->live = 1;
y_direction(dda->y_direction); }
z_direction(dda->z_direction);
e_direction(dda->e_direction);
// ensure this dda starts
dda->live = 1;
// set timeout for first step // set timeout for first step
setTimer(dda->c >> 8); setTimer(dda->c >> 8);
@ -347,6 +357,7 @@ void dda_step(DDA *dda) {
#define Y_CAN_STEP 2 #define Y_CAN_STEP 2
#define Z_CAN_STEP 4 #define Z_CAN_STEP 4
#define E_CAN_STEP 8 #define E_CAN_STEP 8
#define DID_STEP 128
// step_option |= can_step(x_min(), x_max(), current_position.X, dda->endpoint.X, dda->x_direction) & X_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(0 , 0 , current_position.X, dda->endpoint.X, dda->x_direction) & X_CAN_STEP; step_option |= can_step(0 , 0 , current_position.X, dda->endpoint.X, dda->x_direction) & X_CAN_STEP;
@ -361,6 +372,7 @@ void dda_step(DDA *dda) {
dda->x_counter -= dda->x_delta; dda->x_counter -= dda->x_delta;
if (dda->x_counter < 0) { if (dda->x_counter < 0) {
x_step(); x_step();
step_option |= DID_STEP;
if (dda->x_direction) if (dda->x_direction)
current_position.X++; current_position.X++;
else else
@ -374,6 +386,7 @@ void dda_step(DDA *dda) {
dda->y_counter -= dda->y_delta; dda->y_counter -= dda->y_delta;
if (dda->y_counter < 0) { if (dda->y_counter < 0) {
y_step(); y_step();
step_option |= DID_STEP;
if (dda->y_direction) if (dda->y_direction)
current_position.Y++; current_position.Y++;
else else
@ -387,6 +400,7 @@ void dda_step(DDA *dda) {
dda->z_counter -= dda->z_delta; dda->z_counter -= dda->z_delta;
if (dda->z_counter < 0) { if (dda->z_counter < 0) {
z_step(); z_step();
step_option |= DID_STEP;
if (dda->z_direction) if (dda->z_direction)
current_position.Z++; current_position.Z++;
else else
@ -400,6 +414,7 @@ void dda_step(DDA *dda) {
dda->e_counter -= dda->e_delta; dda->e_counter -= dda->e_delta;
if (dda->e_counter < 0) { if (dda->e_counter < 0) {
e_step(); e_step();
step_option |= DID_STEP;
if (dda->e_direction) if (dda->e_direction)
current_position.E++; current_position.E++;
else else
@ -410,11 +425,11 @@ void dda_step(DDA *dda) {
} }
#if STEP_INTERRUPT_INTERRUPTIBLE #if STEP_INTERRUPT_INTERRUPTIBLE
// since we have sent steps to all the motors that will be stepping and the rest of this function isn't so time critical, // since we have sent steps to all the motors that will be stepping and the rest of this function isn't so time critical,
// this interrupt can now be interruptible // this interrupt can now be interruptible
// however we must ensure that we don't step again while computing the below, so disable *this* interrupt but allow others to fire // however we must ensure that we don't step again while computing the below, so disable *this* interrupt but allow others to fire
disableTimerInterrupt(); // disableTimerInterrupt();
sei(); sei();
#endif #endif
// linear acceleration magic, courtesy of http://www.embedded.com/columns/technicalinsights/56800129?printable=true // linear acceleration magic, courtesy of http://www.embedded.com/columns/technicalinsights/56800129?printable=true
@ -426,12 +441,6 @@ void dda_step(DDA *dda) {
dda->c = (int32_t) dda->c - ((int32_t) (dda->c * 2) / dda->n); dda->c = (int32_t) dda->c - ((int32_t) (dda->c * 2) / dda->n);
dda->n += 4; dda->n += 4;
setTimer(dda->c >> 8); setTimer(dda->c >> 8);
// debug
if (0) {
serwrite_uint32(dda->c >> 8);
serial_writestr_P(PSTR("/"));
}
} }
else if (dda->c != dda->end_c) { else if (dda->c != dda->end_c) {
dda->c = dda->end_c; dda->c = dda->end_c;
@ -440,16 +449,19 @@ void dda_step(DDA *dda) {
// else we are already at target speed // else we are already at target speed
} }
if (step_option) if (step_option & DID_STEP) {
// we stepped, reset timeout // we stepped, reset timeout
steptimeout = 0; steptimeout = 0;
// if we could do anything at all, we're still running // if we could do anything at all, we're still running
// otherwise, must have finished // otherwise, must have finished
}
else { else {
dda->live = 0; dda->live = 0;
// reset E- always relative
current_position.E = 0;
// linear acceleration code doesn't alter F during a move, so we must update it here // linear acceleration code doesn't alter F during a move, so we must update it here
// in theory, we *could* update F, but that would require a divide in interrupt context which should be avoided if at all possible // in theory, we *could* update F every step, but that would require a divide in interrupt context which should be avoided if at all possible
current_position.F = dda->endpoint.F; current_position.F = dda->endpoint.F;
} }

View File

@ -29,6 +29,9 @@ typedef struct {
uint8_t live :1; uint8_t live :1;
uint8_t accel :1; uint8_t accel :1;
// wait for temperature to stabilise flag
uint8_t waitfor_temp :1;
// directions // directions
uint8_t x_direction :1; uint8_t x_direction :1;
uint8_t y_direction :1; uint8_t y_direction :1;

View File

@ -8,7 +8,7 @@
uint8_t mb_head = 0; uint8_t mb_head = 0;
uint8_t mb_tail = 0; uint8_t mb_tail = 0;
DDA movebuffer[MOVEBUFFER_SIZE]; DDA movebuffer[MOVEBUFFER_SIZE] __attribute__ ((__section__ (".bss")));
uint8_t queue_full() { uint8_t queue_full() {
return (((mb_tail - mb_head - 1) & (MOVEBUFFER_SIZE - 1)) == 0)?255:0; return (((mb_tail - mb_head - 1) & (MOVEBUFFER_SIZE - 1)) == 0)?255:0;
@ -42,13 +42,43 @@ void enqueue(TARGET *t) {
enableTimerInterrupt(); enableTimerInterrupt();
} }
void enqueue_temp_wait() {
// don't call this function when the queue is full, but just in case, wait for a move to complete and free up the space for the passed target
while (queue_full())
delay(WAITING_DELAY);
uint8_t h = mb_head;
h++;
if (h == MOVEBUFFER_SIZE)
h = 0;
// wait for temp flag
movebuffer[h].waitfor_temp = 1;
movebuffer[h].nullmove = 0;
#if (F_CPU & 0xFF000000) == 0
// set "step" timeout to 1 second
movebuffer[h].c = F_CPU << 8;
#else
// set "step" timeout to maximum
movebuffer[h].c = 0xFFFFFF00;
#endif
mb_head = h;
#ifdef XONXOFF
// if queue is full, stop transmition
if (queue_full())
xoff();
#endif
// fire up in case we're not running yet
enableTimerInterrupt();
}
void next_move() { void next_move() {
if (queue_empty()) { if (queue_empty()) {
#if STEP_INTERRUPT_INTERRUPTIBLE // memcpy(&startpoint, &current_position, sizeof(TARGET));
#else startpoint.E = current_position.E = 0;
disableTimerInterrupt();
#endif
memcpy(&startpoint, &current_position, sizeof(TARGET));
} }
else { else {
// next item // next item

View File

@ -23,6 +23,9 @@ uint8_t queue_empty(void);
// add a new target to the queue // add a new target to the queue
void enqueue(TARGET *t); void enqueue(TARGET *t);
// add a wait for target temp to the queue
void enqueue_temp_wait(void);
// called from step timer when current move is complete // called from step timer when current move is complete
void next_move(void) __attribute__ ((hot)); void next_move(void) __attribute__ ((hot));

3
mendel/debug.c Normal file
View File

@ -0,0 +1,3 @@
#include "debug.h"
volatile uint8_t debug_flags;

21
mendel/debug.h Normal file
View File

@ -0,0 +1,21 @@
#ifndef _DEBUG_H
#define _DEBUG_H
#include <stdint.h>
#ifdef DEBUG
#define DEBUG_PID 1
#define DEBUG_DDA 2
#define DEBUG_POSITION 4
#else
// by setting these to zero, the compiler should optimise the relevant code out
#define DEBUG_PID 0
#define DEBUG_DDA 0
#define DEBUG_POSITION 0
#endif
#define DEBUG_ECHO 128
extern volatile uint8_t debug_flags;
#endif /* _DEBUG_H */

View File

@ -92,10 +92,16 @@ mendel_setup() {
stty 115200 raw ignbrk -hup -echo ixon ixoff < /dev/arduino stty 115200 raw ignbrk -hup -echo ixon ixoff < /dev/arduino
} }
mendel_reset() {
stty hup < /dev/arduino
stty hup < /dev/arduino
mendel_setup
}
mendel_cmd() { mendel_cmd() {
( (
IFS=$' \t\n' IFS=$' \t\n'
LN=0 RSC=0
cmd="$*" cmd="$*"
echo "$cmd" >&3; echo "$cmd" >&3;
while [ "$REPLY" != "OK" ] while [ "$REPLY" != "OK" ]
@ -105,6 +111,17 @@ mendel_cmd() {
then then
echo "$REPLY" echo "$REPLY"
fi fi
if [[ "$REPLY" =~ ^RESEND ]]
then
if [ "$RSC" -le 3 ]
then
echo "$cmd" >&3
RSC=$(( $RSC + 1 ))
else
REPLY="OK"
echo "Too many retries: aborting" >&2
fi
fi
LN=$(( $LN + 1 )) LN=$(( $LN + 1 ))
done done
) 3<>/dev/arduino; ) 3<>/dev/arduino;
@ -113,15 +130,26 @@ mendel_cmd() {
mendel_cmd_hr() { mendel_cmd_hr() {
( (
IFS=$' \t\n' IFS=$' \t\n'
LN=0
cmd="$*" cmd="$*"
echo "$cmd" >&3; RSC=0
echo "$cmd" >&3
echo "> $cmd" echo "> $cmd"
while [ "$REPLY" != "OK" ] while [ "$REPLY" != "OK" ]
do do
read -u 3 read -u 3
echo "< $REPLY" echo "< $REPLY"
LN=$(( $LN + 1 )) if [[ "$REPLY" =~ ^RESEND ]]
then
if [ "$RSC" -le 3 ]
then
echo "$cmd" >&3
echo "> $cmd"
RSC=$(( $RSC + 1))
else
REPLY="OK"
echo "Too many retries: aborting" >&2
fi
fi
done done
) 3<>/dev/arduino; ) 3<>/dev/arduino;
} }

View File

@ -11,17 +11,15 @@
#include "dda.h" #include "dda.h"
#include "clock.h" #include "clock.h"
#include "watchdog.h" #include "watchdog.h"
#include "debug.h"
uint8_t option_bitfield; uint8_t last_field = 0;
#define OPTION_COMMENT 128
#define OPTION_CHECKSUM 64
#define OPTION_ECHO 32
decfloat read_digit;
const char alphabet[] = "GMXYZEFSPN*"; const char alphabet[] = "GMXYZEFSPN*";
GCODE_COMMAND next_target = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, { 0, 0, 0, 0, 0 }, 0, 0, 0, 0, 0, 0 }; decfloat read_digit __attribute__ ((__section__ (".bss")));
GCODE_COMMAND next_target __attribute__ ((__section__ (".bss")));
/* /*
utility functions utility functions
@ -105,11 +103,9 @@ void SpecialMoveE(int32_t e, uint32_t f) {
****************************************************************************/ ****************************************************************************/
void scan_char(uint8_t c) { void scan_char(uint8_t c) {
static uint8_t last_field = 0;
// move this below switch(c) if the asterisk isn't included in the checksum // move this below switch(c) if the asterisk isn't included in the checksum
#define crc(a, b) (a ^ b) #define crc(a, b) (a ^ b)
if ((option_bitfield & OPTION_CHECKSUM) == 0) if (next_target.seen_checksum == 0)
next_target.checksum_calculated = crc(next_target.checksum_calculated, c); next_target.checksum_calculated = crc(next_target.checksum_calculated, c);
// uppercase // uppercase
@ -123,14 +119,12 @@ void scan_char(uint8_t c) {
switch (last_field) { switch (last_field) {
case 'G': case 'G':
next_target.G = read_digit.mantissa; next_target.G = read_digit.mantissa;
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_uint8(next_target.G); serwrite_uint8(next_target.G);
break; break;
case 'M': case 'M':
next_target.M = read_digit.mantissa; next_target.M = read_digit.mantissa;
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_uint8(next_target.M); serwrite_uint8(next_target.M);
break; break;
case 'X': case 'X':
@ -138,8 +132,7 @@ void scan_char(uint8_t c) {
next_target.target.X = decfloat_to_int(&read_digit, STEPS_PER_IN_X, 1); next_target.target.X = decfloat_to_int(&read_digit, STEPS_PER_IN_X, 1);
else else
next_target.target.X = decfloat_to_int(&read_digit, STEPS_PER_MM_X, 1); next_target.target.X = decfloat_to_int(&read_digit, STEPS_PER_MM_X, 1);
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_int32(next_target.target.X); serwrite_int32(next_target.target.X);
break; break;
case 'Y': case 'Y':
@ -147,8 +140,7 @@ void scan_char(uint8_t c) {
next_target.target.Y = decfloat_to_int(&read_digit, STEPS_PER_IN_Y, 1); next_target.target.Y = decfloat_to_int(&read_digit, STEPS_PER_IN_Y, 1);
else else
next_target.target.Y = decfloat_to_int(&read_digit, STEPS_PER_MM_Y, 1); next_target.target.Y = decfloat_to_int(&read_digit, STEPS_PER_MM_Y, 1);
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_int32(next_target.target.Y); serwrite_int32(next_target.target.Y);
break; break;
case 'Z': case 'Z':
@ -156,8 +148,7 @@ void scan_char(uint8_t c) {
next_target.target.Z = decfloat_to_int(&read_digit, STEPS_PER_IN_Z, 1); next_target.target.Z = decfloat_to_int(&read_digit, STEPS_PER_IN_Z, 1);
else else
next_target.target.Z = decfloat_to_int(&read_digit, STEPS_PER_MM_Z, 1); next_target.target.Z = decfloat_to_int(&read_digit, STEPS_PER_MM_Z, 1);
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_int32(next_target.target.Z); serwrite_int32(next_target.target.Z);
break; break;
case 'E': case 'E':
@ -165,8 +156,7 @@ void scan_char(uint8_t c) {
next_target.target.E = decfloat_to_int(&read_digit, STEPS_PER_IN_E, 1); next_target.target.E = decfloat_to_int(&read_digit, STEPS_PER_IN_E, 1);
else else
next_target.target.E = decfloat_to_int(&read_digit, STEPS_PER_MM_E, 1); next_target.target.E = decfloat_to_int(&read_digit, STEPS_PER_MM_E, 1);
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_uint32(next_target.target.E); serwrite_uint32(next_target.target.E);
break; break;
case 'F': case 'F':
@ -175,23 +165,21 @@ void scan_char(uint8_t c) {
next_target.target.F = decfloat_to_int(&read_digit, 254, 10); next_target.target.F = decfloat_to_int(&read_digit, 254, 10);
else else
next_target.target.F = decfloat_to_int(&read_digit, 1, 1); next_target.target.F = decfloat_to_int(&read_digit, 1, 1);
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_uint32(next_target.target.F); serwrite_uint32(next_target.target.F);
break; break;
case 'S': case 'S':
// if this is temperature, multiply by 4 to convert to quarter-degree units // if this is temperature, multiply by 4 to convert to quarter-degree units
// cosmetically this should be done in the temperature section, // cosmetically this should be done in the temperature section,
// but it takes less code, less memory and loses no precision if we do it here instead // but it takes less code, less memory and loses no precision if we do it here instead
if (next_target.M == 104) if ((next_target.M == 104) || (next_target.M == 109))
next_target.S = decfloat_to_int(&read_digit, 4, 1); next_target.S = decfloat_to_int(&read_digit, 4, 1);
// if this is heater PID stuff, multiply by PID_SCALE because we divide by PID_SCALE later on // if this is heater PID stuff, multiply by PID_SCALE because we divide by PID_SCALE later on
else if ((next_target.M >= 130) && (next_target.M <= 132)) else if ((next_target.M >= 130) && (next_target.M <= 132))
next_target.S = decfloat_to_int(&read_digit, PID_SCALE, 1); next_target.S = decfloat_to_int(&read_digit, PID_SCALE, 1);
else else
next_target.S = decfloat_to_int(&read_digit, 1, 1); next_target.S = decfloat_to_int(&read_digit, 1, 1);
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_uint16(next_target.S); serwrite_uint16(next_target.S);
break; break;
case 'P': case 'P':
@ -200,18 +188,17 @@ void scan_char(uint8_t c) {
next_target.P = decfloat_to_int(&read_digit, 1000, 1); next_target.P = decfloat_to_int(&read_digit, 1000, 1);
else else
next_target.P = decfloat_to_int(&read_digit, 1, 1); next_target.P = decfloat_to_int(&read_digit, 1, 1);
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serwrite_uint16(next_target.P); serwrite_uint16(next_target.P);
break; break;
case 'N': case 'N':
next_target.N = decfloat_to_int(&read_digit, 1, 1); next_target.N = decfloat_to_int(&read_digit, 1, 1);
if (option_bitfield & OPTION_ECHO) if (debug_flags & DEBUG_ECHO)
serwrite_uint32(next_target.N); serwrite_uint32(next_target.N);
break; break;
case '*': case '*':
next_target.checksum_read = decfloat_to_int(&read_digit, 1, 1); next_target.checksum_read = decfloat_to_int(&read_digit, 1, 1);
if (option_bitfield & OPTION_ECHO) if (debug_flags & DEBUG_ECHO)
serwrite_uint8(next_target.checksum_read); serwrite_uint8(next_target.checksum_read);
break; break;
} }
@ -224,12 +211,11 @@ void scan_char(uint8_t c) {
} }
// skip comments // skip comments
if ((option_bitfield & OPTION_COMMENT) == 0) { if (next_target.seen_comment == 0) {
// new field? // new field?
if (indexof(c, alphabet) >= 0) { if (indexof(c, alphabet) >= 0) {
last_field = c; last_field = c;
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serial_writechar(c); serial_writechar(c);
} }
@ -272,12 +258,13 @@ void scan_char(uint8_t c) {
break; break;
case '*': case '*':
next_target.seen_checksum = 1; next_target.seen_checksum = 1;
option_bitfield |= OPTION_CHECKSUM; // option_bitfield |= OPTION_CHECKSUM;
break; break;
// comments // comments
case ';': case ';':
option_bitfield |= OPTION_COMMENT; next_target.seen_comment = 1;
// option_bitfield |= OPTION_COMMENT;
break; break;
// now for some numeracy // now for some numeracy
@ -305,8 +292,7 @@ void scan_char(uint8_t c) {
// end of line // end of line
if ((c == 10) || (c == 13)) { if ((c == 10) || (c == 13)) {
// if (DEBUG) if (debug_flags & DEBUG_ECHO)
if (option_bitfield & OPTION_ECHO)
serial_writechar(c); serial_writechar(c);
// process // process
if (next_target.seen_G || next_target.seen_M) { if (next_target.seen_G || next_target.seen_M) {
@ -332,18 +318,20 @@ void scan_char(uint8_t c) {
next_target.N_expected++; next_target.N_expected++;
} }
else { else {
serial_writestr_P(PSTR("RESEND: BAD CHECKSUM\n")); serial_writestr_P(PSTR("RESEND: BAD CHECKSUM: EXPECTED "));
serwrite_uint8(next_target.checksum_calculated);
serial_writestr_P(PSTR("\n"));
} }
} }
else { else {
serial_writestr_P(PSTR("RESEND: BAD LINE NUMBER\n")); serial_writestr_P(PSTR("RESEND: BAD LINE NUMBER: EXPECTED "));
serwrite_uint32(next_target.N_expected);
serial_writestr_P(PSTR("\n"));
} }
} }
// reset 'seen comment' and 'receiving checksum'
option_bitfield &= (OPTION_COMMENT | OPTION_CHECKSUM);
// reset variables // 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 = next_target.N = next_target.checksum_read = next_target.checksum_calculated = 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 = next_target.seen_N = next_target.seen_checksum = next_target.seen_comment = next_target.checksum_read = next_target.checksum_calculated = 0;
last_field = 0; last_field = 0;
read_digit.sign = 0; read_digit.sign = 0;
read_digit.mantissa = 0; read_digit.mantissa = 0;
@ -363,10 +351,14 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
gcmd->target.X += startpoint.X; gcmd->target.X += startpoint.X;
gcmd->target.Y += startpoint.Y; gcmd->target.Y += startpoint.Y;
gcmd->target.Z += startpoint.Z; gcmd->target.Z += startpoint.Z;
gcmd->target.E += startpoint.E;
} }
// E ALWAYS relative, otherwise we overflow our registers after only a few layers
// gcmd->target.E += startpoint.E;
// easier way to do this
// startpoint.E = 0;
// moved to dda.c, end of dda_create() and dda_queue.c, next_move()
// explicitly make unseen values equal to startpoint, otherwise relative position mode is a clusterfuck // explicitly make unseen values equal to startpoint, otherwise relative position mode gets messy
if (gcmd->seen_X == 0) if (gcmd->seen_X == 0)
gcmd->target.X = startpoint.X; gcmd->target.X = startpoint.X;
if (gcmd->seen_Y == 0) if (gcmd->seen_Y == 0)
@ -511,18 +503,21 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
serial_writechar('\n'); serial_writechar('\n');
} }
} }
if (gcmd->seen_M) { else if (gcmd->seen_M) {
switch (gcmd->M) { switch (gcmd->M) {
// M101- extruder on // M101- extruder on
case 101: case 101:
serial_writestr_P(PSTR("Waiting for extruder to reach target temperature\n")); if (temp_achieved() == 0) {
// here we wait until target temperature is reached, and emulate main loop so the temperature can actually be updated // serial_writestr_P(PSTR("Waiting for extruder to reach target temperature\n"));
while (!temp_achieved()) { // // here we wait until target temperature is reached, and emulate main loop so the temperature can actually be updated
ifclock(CLOCK_FLAG_250MS) { // while (temp_achieved() == 0) {
// this is cosmetically nasty, but exactly what needs to happen // ifclock(CLOCK_FLAG_250MS) {
void clock_250ms(void); // // this is cosmetically nasty, but exactly what needs to happen
clock_250ms(); // void clock_250ms(void);
} // clock_250ms();
// }
// }
enqueue_temp_wait();
} }
do { do {
// backup feedrate, move E very quickly then restore feedrate // backup feedrate, move E very quickly then restore feedrate
@ -566,14 +561,52 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
// M106- fan on // M106- fan on
#ifdef FAN_PIN #ifdef FAN_PIN
case 106: case 106:
WRITE(FAN_PIN, 1); enable_fan();
break; break;
// M107- fan off // M107- fan off
case 107: case 107:
WRITE(FAN_PIN, 0); disable_fan();
break; break;
#endif #endif
// M109- set temp and wait
case 109:
temp_set(gcmd->S);
if (gcmd->S) {
enable_heater();
power_on();
}
else {
disable_heater();
}
enqueue_temp_wait();
// while (!temp_achieved()) {
// ifclock(CLOCK_FLAG_250MS) {
// // this is cosmetically nasty, but exactly what needs to happen
// void clock_250ms(void);
// clock_250ms();
// }
// }
break;
// M110- set line number
case 110:
gcmd->N_expected = gcmd->S - 1;
break;
// M111- set debug level
#ifdef DEBUG
case 111:
debug_flags = gcmd->S;
break;
#endif
// M112- immediate stop
case 112:
disableTimerInterrupt();
power_off();
break;
// M113- extruder PWM
// M114- report XYZEF to host
// M130- heater P factor // M130- heater P factor
case 130: case 130:
if (gcmd->seen_S) if (gcmd->seen_S)
@ -599,20 +632,22 @@ void process_gcode_command(GCODE_COMMAND *gcmd) {
temp_save_settings(); temp_save_settings();
break; break;
#ifdef DEBUG
// M140- echo off // M140- echo off
case 140: case 140:
option_bitfield &= ~OPTION_ECHO; debug_flags &= ~DEBUG_ECHO;
serial_writestr_P(PSTR("Echo off\n")); serial_writestr_P(PSTR("Echo off\n"));
break; break;
// M141- echo on // M141- echo on
case 141: case 141:
option_bitfield |= OPTION_ECHO; debug_flags |= DEBUG_ECHO;
serial_writestr_P(PSTR("Echo on\n")); serial_writestr_P(PSTR("Echo on\n"));
break; break;
#endif
// DEBUG: return current position // DEBUG: return current position
case 250: case 250:
serial_writestr_P(PSTR("\n{X:")); serial_writestr_P(PSTR("{X:"));
serwrite_int32(current_position.X); serwrite_int32(current_position.X);
serial_writestr_P(PSTR(",Y:")); serial_writestr_P(PSTR(",Y:"));
serwrite_int32(current_position.Y); serwrite_int32(current_position.Y);

View File

@ -26,6 +26,7 @@ typedef struct {
uint8_t seen_P :1; uint8_t seen_P :1;
uint8_t seen_N :1; uint8_t seen_N :1;
uint8_t seen_checksum :1; uint8_t seen_checksum :1;
uint8_t seen_comment :1;
uint8_t option_relative :1; uint8_t option_relative :1;
uint8_t option_inches :1; uint8_t option_inches :1;

View File

@ -62,13 +62,15 @@
// http://blog.arcol.hu/?p=157 may help with this next one // http://blog.arcol.hu/?p=157 may help with this next one
// I haven't tuned this at all- it's just a placeholder until I read the above carefully enough // I haven't tuned this at all- it's just a placeholder until I read the above carefully enough
// does this refer to filament or extrudate? extrudate depends on XY distance vs E distance.. hm lets go with filament // does this refer to filament or extrudate? extrudate depends on XY distance vs E distance.. hm lets go with filament
#define STEPS_PER_MM_E ((uint32_t) ((E_STEPS_PER_REV / (EXTRUDER_SHAFT_RADIUS * PI * EXTRUDER_INLET_DIAMETER)) + 0.5)) // #define STEPS_PER_MM_E ((uint32_t) ((E_STEPS_PER_REV / (EXTRUDER_SHAFT_RADIUS * PI * EXTRUDER_INLET_DIAMETER / EXTRUDER_NOZZLE_DIAMETER)) + 0.5))
#define STEPS_PER_MM_E ((uint32_t) ((E_STEPS_PER_REV * EXTRUDER_NOZZLE_DIAMETER / (EXTRUDER_SHAFT_RADIUS * PI * EXTRUDER_INLET_DIAMETER)) + 0.5))
// same as above with 25.4 scale factor // same as above with 25.4 scale factor
#define STEPS_PER_IN_X ((uint32_t) ((25.4 * X_STEPS_PER_REV / X_COG_CIRCUMFERENCE) + 0.5)) #define STEPS_PER_IN_X ((uint32_t) ((25.4 * X_STEPS_PER_REV / X_COG_CIRCUMFERENCE) + 0.5))
#define STEPS_PER_IN_Y ((uint32_t) ((25.4 * Y_STEPS_PER_REV / Y_COG_CIRCUMFERENCE) + 0.5)) #define STEPS_PER_IN_Y ((uint32_t) ((25.4 * Y_STEPS_PER_REV / Y_COG_CIRCUMFERENCE) + 0.5))
#define STEPS_PER_IN_Z ((uint32_t) ((25.4 * Z_STEPS_PER_REV * Z_GEAR_RATIO) + 0.5)) #define STEPS_PER_IN_Z ((uint32_t) ((25.4 * Z_STEPS_PER_REV * Z_GEAR_RATIO) + 0.5))
#define STEPS_PER_IN_E ((uint32_t) ((25.4 * E_STEPS_PER_REV / (EXTRUDER_SHAFT_RADIUS * PI * EXTRUDER_INLET_DIAMETER)) + 0.5)) #define STEPS_PER_IN_E ((uint32_t) ((25.4 * E_STEPS_PER_REV * EXTRUDER_NOZZLE_DIAMETER / (EXTRUDER_SHAFT_RADIUS * PI * EXTRUDER_INLET_DIAMETER)) + 0.5))
// inverse, used in distance calculation during DDA setup // inverse, used in distance calculation during DDA setup
#define UM_PER_STEP_X ((uint32_t) ((1000.0 / STEPS_PER_MM_X) + 0.5)) #define UM_PER_STEP_X ((uint32_t) ((1000.0 / STEPS_PER_MM_X) + 0.5))

View File

@ -16,10 +16,8 @@
#include "temp.h" #include "temp.h"
#include "sermsg.h" #include "sermsg.h"
#include "watchdog.h" #include "watchdog.h"
#include "debug.h"
#ifndef DEBUG #include "sersendf.h"
#define DEBUG 0
#endif
void io_init(void) { void io_init(void) {
// disable modules we don't use // disable modules we don't use
@ -44,17 +42,19 @@ void io_init(void) {
#ifdef HEATER_PIN #ifdef HEATER_PIN
WRITE(HEATER_PIN, 0); SET_OUTPUT(HEATER_PIN); WRITE(HEATER_PIN, 0); SET_OUTPUT(HEATER_PIN);
#ifdef HEATER_PWM
// setup PWM timer: fast PWM, no prescaler
TCCR0A = MASK(WGM01) | MASK(WGM00);
TCCR0B = MASK(CS00);
TIMSK0 = 0;
OCR0A = 0;
#endif
#endif #endif
#ifdef FAN_PIN #ifdef FAN_PIN
disable_fan(); WRITE(FAN_PIN, 0); SET_OUTPUT(FAN_PIN);
#endif
#if defined(HEATER_PWM) || defined(FAN_PWM)
// setup PWM timer: fast PWM, no prescaler
TCCR0A = MASK(WGM01) | MASK(WGM00);
TCCR0B = MASK(CS00);
TIMSK0 = 0;
OCR0A = 0;
OCR0B = 255;
#endif #endif
#ifdef STEPPER_ENABLE_PIN #ifdef STEPPER_ENABLE_PIN
@ -115,32 +115,34 @@ void clock_250ms(void) {
steptimeout++; steptimeout++;
ifclock(CLOCK_FLAG_1S) { ifclock(CLOCK_FLAG_1S) {
if (DEBUG) { if (debug_flags & DEBUG_POSITION) {
// current position // current position
serial_writestr_P(PSTR("Pos: ")); // serial_writestr_P(PSTR("Pos: "));
serwrite_int32(current_position.X); // serwrite_int32(current_position.X);
serial_writechar(','); // serial_writechar(',');
serwrite_int32(current_position.Y); // serwrite_int32(current_position.Y);
serial_writechar(','); // serial_writechar(',');
serwrite_int32(current_position.Z); // serwrite_int32(current_position.Z);
serial_writechar(','); // serial_writechar(',');
serwrite_int32(current_position.E); // serwrite_int32(current_position.E);
serial_writechar(','); // serial_writechar(',');
serwrite_uint32(current_position.F); // serwrite_uint32(current_position.F);
serial_writechar('\n'); // serial_writechar('\n');
sersendf_P(PSTR("Pos: %ld,%ld,%ld,%ld,%lu\n"), current_position.X, current_position.Y, current_position.Z, current_position.E, current_position.F);
// target position // target position
serial_writestr_P(PSTR("Dst: ")); // serial_writestr_P(PSTR("Dst: "));
serwrite_int32(movebuffer[mb_tail].endpoint.X); // serwrite_int32(movebuffer[mb_tail].endpoint.X);
serial_writechar(','); // serial_writechar(',');
serwrite_int32(movebuffer[mb_tail].endpoint.Y); // serwrite_int32(movebuffer[mb_tail].endpoint.Y);
serial_writechar(','); // serial_writechar(',');
serwrite_int32(movebuffer[mb_tail].endpoint.Z); // serwrite_int32(movebuffer[mb_tail].endpoint.Z);
serial_writechar(','); // serial_writechar(',');
serwrite_int32(movebuffer[mb_tail].endpoint.E); // serwrite_int32(movebuffer[mb_tail].endpoint.E);
serial_writechar(','); // serial_writechar(',');
serwrite_uint32(movebuffer[mb_tail].endpoint.F); // serwrite_uint32(movebuffer[mb_tail].endpoint.F);
serial_writechar('\n'); // serial_writechar('\n');
sersendf_P(PSTR("Dst: %ld,%ld,%ld,%ld,%lu\n"), movebuffer[mb_tail].endpoint.X, movebuffer[mb_tail].endpoint.Y, movebuffer[mb_tail].endpoint.Z, movebuffer[mb_tail].endpoint.E, movebuffer[mb_tail].endpoint.F);
// Queue // Queue
print_queue(); print_queue();

View File

@ -55,7 +55,7 @@
#define HEATER_PWM OCR0A #define HEATER_PWM OCR0A
#define FAN_PIN DIO5 #define FAN_PIN DIO5
// #define FAN_PIN_PWM OC0B #define FAN_PWM OCR0B
/* /*
X Stepper X Stepper
@ -124,8 +124,13 @@
*/ */
#ifdef FAN_PIN #ifdef FAN_PIN
#define enable_fan() WRITE(FAN_PIN, 1) #ifdef FAN_PWM
#define disable_fan() do { WRITE(FAN_PIN, 0); SET_OUTPUT(FAN_PIN); } while (0) #define enable_fan() do { TCCR0A |= MASK(COM0B1); } while (0)
#define disable_fan() do { TCCR0A &= ~MASK(COM0B1); } while (0)
#else
#define enable_fan() WRITE(FAN_PIN, 1)
#define disable_fan() WRITE(FAN_PIN, 0);
#endif
#else #else
#define enable_fan() if (0) {} #define enable_fan() if (0) {}
#define disable_fan() if (0) {} #define disable_fan() if (0) {}

View File

@ -150,6 +150,14 @@ void serial_writeblock(void *data, int datalen)
serial_writechar(((uint8_t *) data)[i]); serial_writechar(((uint8_t *) data)[i]);
} }
void serial_writestr(uint8_t *data)
{
uint8_t i = 0;
// yes, this is *supposed* to be assignment rather than comparison, so we break when r is assigned zero
for (uint8_t r; (r = data[i]); i++)
serial_writechar(r);
}
/* /*
Write from FLASH Write from FLASH
*/ */

View File

@ -21,6 +21,8 @@ void serial_writechar(uint8_t data);
// uint8_t serial_recvblock(uint8_t *block, int blocksize); // uint8_t serial_recvblock(uint8_t *block, int blocksize);
void serial_writeblock(void *data, int datalen); void serial_writeblock(void *data, int datalen);
void serial_writestr(uint8_t *data);
// write from flash // write from flash
void serial_writechar_P(PGM_P data); void serial_writechar_P(PGM_P data);
void serial_writeblock_P(PGM_P data, int datalen); void serial_writeblock_P(PGM_P data, int datalen);

129
mendel/sersendf.c Normal file
View File

@ -0,0 +1,129 @@
#include "sersendf.h"
#include <stdarg.h>
#include <avr/pgmspace.h>
#include "serial.h"
#include "sermsg.h"
PGM_P str_ox = "0x";
void sersendf(char *format, ...) {
va_list args;
va_start(args, format);
uint16_t i = 0;
uint8_t c = 1, j = 0;
for (; c != 0; i++) {
c = format[i];
if (j) {
switch(c) {
case 'l':
j = 4;
case 'u':
if (j == 4)
serwrite_uint32(va_arg(args, uint32_t));
else
serwrite_uint16(va_arg(args, uint16_t));
j = 0;
break;
case 'd':
if (j == 4)
serwrite_int32(va_arg(args, int32_t));
else
serwrite_int16(va_arg(args, int16_t));
j = 0;
break;
case 'p':
case 'x':
serial_writestr_P(str_ox);
if (j == 4)
serwrite_hex32(va_arg(args, uint32_t));
else
serwrite_hex16(va_arg(args, uint16_t));
j = 0;
break;
case 'c':
serial_writechar(va_arg(args, uint16_t));
j = 0;
break;
case 's':
serial_writestr(va_arg(args, uint8_t *));
j = 0;
break;
default:
j = 0;
break;
}
}
else {
if (c == '%') {
j = 2;
}
else {
serial_writechar(c);
}
}
}
va_end(args);
}
void sersendf_P(PGM_P format, ...) {
va_list args;
va_start(args, format);
uint16_t i = 0;
uint8_t c = 1, j = 0;
for (; c != 0; i++) {
c = pgm_read_byte(&format[i]);
if (j) {
switch(c) {
case 's':
j = 1;
break;
case 'l':
j = 4;
break;
case 'u':
if (j == 4)
serwrite_uint32(va_arg(args, uint32_t));
else
serwrite_uint16(va_arg(args, uint16_t));
j = 0;
break;
case 'd':
if (j == 4)
serwrite_int32(va_arg(args, int32_t));
else
serwrite_int16(va_arg(args, int16_t));
j = 0;
break;
case 'x':
if (j == 4)
serwrite_hex32(va_arg(args, uint32_t));
else if (j == 1)
serwrite_hex8(va_arg(args, uint16_t));
else
serwrite_hex16(va_arg(args, uint16_t));
j = 0;
break;
case 'c':
serial_writechar(va_arg(args, uint16_t));
case 'p':
serwrite_hex16(va_arg(args, uint16_t));
default:
j = 0;
break;
}
}
else {
if (c == '%') {
j = 2;
}
else {
serial_writechar(c);
}
}
}
va_end(args);
}

9
mendel/sersendf.h Normal file
View File

@ -0,0 +1,9 @@
#ifndef _SERSENDF_H
#define _SERSENDF_H
#include <avr/pgmspace.h>
void sersendf(char *format, ...) __attribute__ ((format (printf, 1, 2)));
void sersendf_P(PGM_P format, ...);
#endif /* _SERSENDF_H */

View File

@ -27,6 +27,8 @@
#include "sermsg.h" #include "sermsg.h"
#include "timer.h" #include "timer.h"
#include "dda.h" #include "dda.h"
#include "sersendf.h"
#include "debug.h"
uint16_t current_temp = 0; uint16_t current_temp = 0;
uint16_t target_temp = 0; uint16_t target_temp = 0;
@ -36,9 +38,9 @@ int16_t heater_i = 0;
int16_t heater_d = 0; int16_t heater_d = 0;
#define DEFAULT_P 4096 #define DEFAULT_P 4096
#define DEFAULT_I 64 #define DEFAULT_I 256
#define DEFAULT_D -12288 #define DEFAULT_D -14336
#define DEFAULT_I_LIMIT 3072 #define DEFAULT_I_LIMIT 768
int32_t p_factor = 0; int32_t p_factor = 0;
int32_t i_factor = 0; int32_t i_factor = 0;
int32_t d_factor = 0; int32_t d_factor = 0;
@ -123,9 +125,6 @@ uint16_t temp_read() {
} }
} }
// if (DEBUG)
// serial_writechar(']');
return 0; return 0;
} }
@ -152,39 +151,59 @@ uint8_t temp_achieved() {
} }
void temp_print() { void temp_print() {
serial_writestr_P(PSTR("T: ")); // serial_writestr_P(PSTR("T: "));
if (temp_flags & TEMP_FLAG_TCOPEN) { if (temp_flags & TEMP_FLAG_TCOPEN) {
serial_writestr_P(PSTR("no thermocouple!")); serial_writestr_P(PSTR("T: no thermocouple!\n"));
} }
else { else {
serwrite_uint16(current_temp >> 2); // serwrite_uint16(current_temp >> 2);
serial_writechar('.'); // serial_writechar('.');
if (current_temp & 3) { // if (current_temp & 3) {
if ((current_temp & 3) == 3) // if ((current_temp & 3) == 3)
serial_writechar('7'); // serial_writechar('7');
else if ((current_temp & 3) == 1) // else if ((current_temp & 3) == 1)
serial_writechar('2'); // serial_writechar('2');
serial_writechar('5'); // serial_writechar('5');
} // }
else { // else {
serial_writechar('0'); // serial_writechar('0');
} // }
// serial_writestr_P(PSTR("°C")); // // serial_writestr_P(PSTR("°C"));
serial_writechar('/'); // serial_writechar('/');
serwrite_uint16(target_temp >> 2); // serwrite_uint16(target_temp >> 2);
serial_writechar('.'); // serial_writechar('.');
if (target_temp & 3) { // if (target_temp & 3) {
if ((target_temp & 3) == 3) // if ((target_temp & 3) == 3)
serial_writechar('7'); // serial_writechar('7');
else if ((target_temp & 3) == 1) // else if ((target_temp & 3) == 1)
serial_writechar('2'); // serial_writechar('2');
serial_writechar('5'); // serial_writechar('5');
} // }
else { // else {
serial_writechar('0'); // serial_writechar('0');
} // }
//
// serial_writestr_P(PSTR(" :"));
// serwrite_uint8(temp_residency);
uint8_t c = 0, t = 0;
if (current_temp & 3)
c = 5;
if ((current_temp & 3) == 1)
c += 20;
else if ((current_temp & 3) == 3)
c += 70;
if (target_temp & 3)
t = 5;
if ((target_temp & 3) == 1)
t += 20;
else if ((target_temp & 3) == 3)
t += 70;
sersendf_P(PSTR("%u.%u/%u.%u :%u\n"), current_temp >> 2, c, target_temp >> 2, t, temp_residency);
} }
serial_writechar('\n'); // serial_writechar('\n');
} }
void temp_tick() { void temp_tick() {
@ -202,15 +221,15 @@ void temp_tick() {
else if (temp_residency < TEMP_RESIDENCY_TIME) else if (temp_residency < TEMP_RESIDENCY_TIME)
temp_residency++; temp_residency++;
// if (DEBUG) // if (debug_flags & DEBUG_PID)
serial_writestr_P(PSTR("T{")); // serial_writestr_P(PSTR("T{"));
int16_t t_error = target_temp - current_temp; int16_t t_error = target_temp - current_temp;
// if (DEBUG) { // if (debug_flags & DEBUG_PID) {
serial_writestr_P(PSTR("E:")); // serial_writestr_P(PSTR("E:"));
serwrite_int16(t_error); // serwrite_int16(t_error);
// } // }
// PID stuff // PID stuff
// proportional // proportional
@ -229,24 +248,26 @@ void temp_tick() {
// heater_d = (current_temp - last_temp); // heater_d = (current_temp - last_temp);
heater_d = current_temp - temp_history[th_p]; heater_d = current_temp - temp_history[th_p];
serial_writestr_P(PSTR(", P:")); // if (debug_flags & DEBUG_PID) {
serwrite_int16(heater_p); // serial_writestr_P(PSTR(", P:"));
serial_writestr_P(PSTR(" * ")); // serwrite_int16(heater_p);
serwrite_int32(p_factor); // serial_writestr_P(PSTR(" * "));
serial_writestr_P(PSTR(" = ")); // serwrite_int32(p_factor);
serwrite_int32((int32_t) heater_p * p_factor / PID_SCALE); // serial_writestr_P(PSTR(" = "));
serial_writestr_P(PSTR(" / I:")); // serwrite_int32((int32_t) heater_p * p_factor / PID_SCALE);
serwrite_int16(heater_i); // serial_writestr_P(PSTR(" / I:"));
serial_writestr_P(PSTR(" * ")); // serwrite_int16(heater_i);
serwrite_int32(i_factor); // serial_writestr_P(PSTR(" * "));
serial_writestr_P(PSTR(" = ")); // serwrite_int32(i_factor);
serwrite_int32((int32_t) heater_i * i_factor / PID_SCALE); // serial_writestr_P(PSTR(" = "));
serial_writestr_P(PSTR(" / D:")); // serwrite_int32((int32_t) heater_i * i_factor / PID_SCALE);
serwrite_int16(heater_d); // serial_writestr_P(PSTR(" / D:"));
serial_writestr_P(PSTR(" * ")); // serwrite_int16(heater_d);
serwrite_int32(d_factor); // serial_writestr_P(PSTR(" * "));
serial_writestr_P(PSTR(" = ")); // serwrite_int32(d_factor);
serwrite_int32((int32_t) heater_d * d_factor / PID_SCALE); // serial_writestr_P(PSTR(" = "));
// serwrite_int32((int32_t) heater_d * d_factor / PID_SCALE);
// }
// combine factors // combine factors
int32_t pid_output_intermed = ( int32_t pid_output_intermed = (
@ -257,17 +278,13 @@ void temp_tick() {
) / PID_SCALE ) / PID_SCALE
); );
serial_writestr_P(PSTR(" # O: ")); // if (debug_flags & DEBUG_PID) {
serwrite_int32(pid_output_intermed); // serial_writestr_P(PSTR(" # O: "));
// serwrite_int32(pid_output_intermed);
// }
// rebase and limit factors // rebase and limit factors
uint8_t pid_output; uint8_t pid_output;
// if (pid_output_intermed > 127)
// pid_output = 255;
// else if (pid_output_intermed < -128)
// pid_output = 0;
// else
// pid_output = (pid_output_intermed + 128);
if (pid_output_intermed > 255) if (pid_output_intermed > 255)
pid_output = 255; pid_output = 255;
else if (pid_output_intermed < 0) else if (pid_output_intermed < 0)
@ -275,10 +292,13 @@ void temp_tick() {
else else
pid_output = pid_output_intermed & 0xFF; pid_output = pid_output_intermed & 0xFF;
// if (DEBUG) { // if (debug_flags & DEBUG_PID) {
serial_writestr_P(PSTR(" = ")); // serial_writestr_P(PSTR(" = "));
serwrite_uint8(pid_output); // serwrite_uint8(pid_output);
// } // }
if (debug_flags & DEBUG_PID)
sersendf_P(PSTR("T{E:%d, P:%d * %ld = %ld / I:%d * %ld = %ld / D:%d * %ld = %ld # O: %ld = %u}\n"), t_error, heater_p, p_factor, (int32_t) heater_p * p_factor / PID_SCALE, heater_i, i_factor, (int32_t) heater_i * i_factor / PID_SCALE, heater_d, d_factor, (int32_t) heater_d * d_factor / PID_SCALE, pid_output_intermed, pid_output);
#ifdef HEATER_PWM #ifdef HEATER_PWM
HEATER_PWM = pid_output; HEATER_PWM = pid_output;
@ -289,7 +309,7 @@ void temp_tick() {
disable_heater(); disable_heater();
#endif #endif
// if (DEBUG) // if (debug_flags & DEBUG_PID)
serial_writestr_P(PSTR("}\n")); // serial_writestr_P(PSTR("}\n"));
} }
} }

View File

@ -6,19 +6,35 @@
#include "dda_queue.h" #include "dda_queue.h"
#include "dda.h" #include "dda.h"
#include "watchdog.h" #include "watchdog.h"
#include "temp.h"
#include "serial.h"
ISR(TIMER1_COMPA_vect) { ISR(TIMER1_COMPA_vect) {
WRITE(SCK, 1); WRITE(SCK, 1);
disableTimerInterrupt();
// do our next step // do our next step
// NOTE: dda_step makes this interrupt interruptible after steps have been sent but before new speed is calculated. // NOTE: dda_step makes this interrupt interruptible after steps have been sent but before new speed is calculated.
if (movebuffer[mb_tail].live) if (movebuffer[mb_tail].live) {
dda_step(&(movebuffer[mb_tail])); if (movebuffer[mb_tail].waitfor_temp) {
#if STEP_INTERRUPT_INTERRUPTIBLE
// this interrupt can now be interruptible
// disableTimerInterrupt();
sei();
#endif
#if STEP_INTERRUPT_INTERRUPTIBLE if (temp_achieved()) {
// this interrupt can now be interruptible movebuffer[mb_tail].live = 0;
disableTimerInterrupt(); serial_writestr_P(PSTR("Temp achieved, next move\n"));
sei(); }
#endif }
else {
dda_step(&(movebuffer[mb_tail]));
}
}
// serial_writechar('!');
// fall directly into dda_start instead of waiting for another step // fall directly into dda_start instead of waiting for another step
if (movebuffer[mb_tail].live == 0) if (movebuffer[mb_tail].live == 0)
@ -27,10 +43,10 @@ ISR(TIMER1_COMPA_vect) {
#if STEP_INTERRUPT_INTERRUPTIBLE #if STEP_INTERRUPT_INTERRUPTIBLE
// return from interrupt in a way that prevents this interrupt nesting with itself at high step rates // return from interrupt in a way that prevents this interrupt nesting with itself at high step rates
cli(); cli();
// check queue, if empty we don't need to interrupt again until re-enabled in dda_create
if (queue_empty() == 0)
enableTimerInterrupt();
#endif #endif
// check queue, if empty we don't need to interrupt again until re-enabled in dda_create
if (queue_empty() == 0)
enableTimerInterrupt();
WRITE(SCK, 0); WRITE(SCK, 0);
} }
@ -44,7 +60,7 @@ void setupTimerInterrupt()
TIMSK1 = 0; TIMSK1 = 0;
//start off with a slow frequency. //start off with a slow frequency.
setTimer(10000); setTimer(F_CPU / 100);
} }
// the following are all from reprap project 5D firmware // the following are all from reprap project 5D firmware