summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authoradrian-bowyer <adrian-bowyer>2009-10-27 15:36:14 +0000
committeradrian-bowyer <adrian-bowyer@cb376a5e-1013-0410-a455-b6b1f9ac8223>2009-10-27 15:36:14 +0000
commit10c63a5bae9a9b32a04559fcdea24df31d16296d (patch)
treed72fc13d99cd8a323ba045933233bebd0ea1cd3c
parent9131a8f91a1fce4313db51959f2ed2352f0f335d (diff)
downloadreprap-10c63a5bae9a9b32a04559fcdea24df31d16296d.tar.gz
reprap-10c63a5bae9a9b32a04559fcdea24df31d16296d.zip
More Updating the Darwin 5D G code firmware.
git-svn-id: https://reprap.svn.sourceforge.net/svnroot/reprap@3329 cb376a5e-1013-0410-a455-b6b1f9ac8223
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/FiveD_GCode_Interpreter.pde404
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/ThermistorTable.h54
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.h174
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.pde423
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/configuration.h.dist184
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.h321
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.pde313
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.h241
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.pde540
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/pins.h149
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/process_g_code.pde527
-rwxr-xr-xtrunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/vectors.h130
12 files changed, 3460 insertions, 0 deletions
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/FiveD_GCode_Interpreter.pde b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/FiveD_GCode_Interpreter.pde
new file mode 100755
index 00000000..1a34193b
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/FiveD_GCode_Interpreter.pde
@@ -0,0 +1,404 @@
+// Yep, this is actually -*- c++ -*-
+
+// Sanguino G-code Interpreter
+// Arduino v1.0 by Mike Ellery - initial software (mellery@gmail.com)
+// v1.1 by Zach Hoeken - cleaned up and did lots of tweaks (hoeken@gmail.com)
+// v1.2 by Chris Meighan - cleanup / G2&G3 support (cmeighan@gmail.com)
+// v1.3 by Zach Hoeken - added thermocouple support and multi-sample temp readings. (hoeken@gmail.com)
+// Sanguino v1.4 by Adrian Bowyer - added the Sanguino; extensive mods... (a.bowyer@bath.ac.uk)
+// Sanguino v1.5 by Adrian Bowyer - implemented 4D Bressenham XYZ+ stepper control... (a.bowyer@bath.ac.uk)
+// Sanguino v1.6 by Adrian Bowyer - implemented RS485 extruders
+
+#ifndef __AVR_ATmega644P__
+#error Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
+#endif
+
+#include <ctype.h>
+#include <HardwareSerial.h>
+#include <avr/pgmspace.h>
+#include "WProgram.h"
+#include "vectors.h"
+#include "configuration.h"
+#include "intercom.h"
+#include "pins.h"
+#include "extruder.h"
+#include "cartesian_dda.h"
+
+// Maintain a list of extruders...
+
+extruder* ex[EXTRUDER_COUNT];
+byte extruder_in_use = 0;
+
+// Text placed in this (terminated with 0) will be transmitted back to the host
+// along with the next G Code acknowledgement.
+char debugstring[20];
+
+#if MOTHERBOARD < 2
+
+// TODO: For some reason, if you declare the following two in the order ex0 ex1 then
+// ex0 won't drive its stepper. They seem fine this way round though. But that's got
+// to be a bug.
+
+#if EXTRUDER_COUNT == 2
+static extruder ex1(EXTRUDER_1_MOTOR_DIR_PIN, EXTRUDER_1_MOTOR_SPEED_PIN , EXTRUDER_1_HEATER_PIN,
+ EXTRUDER_1_FAN_PIN, EXTRUDER_1_TEMPERATURE_PIN, EXTRUDER_1_VALVE_DIR_PIN,
+ EXTRUDER_1_VALVE_ENABLE_PIN, EXTRUDER_1_STEP_ENABLE_PIN);
+#endif
+
+static extruder ex0(EXTRUDER_0_MOTOR_DIR_PIN, EXTRUDER_0_MOTOR_SPEED_PIN , EXTRUDER_0_HEATER_PIN,
+ EXTRUDER_0_FAN_PIN, EXTRUDER_0_TEMPERATURE_PIN, EXTRUDER_0_VALVE_DIR_PIN,
+ EXTRUDER_0_VALVE_ENABLE_PIN, EXTRUDER_0_STEP_ENABLE_PIN);
+
+
+#else
+
+#if EXTRUDER_COUNT == 2
+static extruder ex1(E1_NAME);
+#endif
+
+static extruder ex0(E0_NAME);
+
+intercom talker;
+
+#endif
+
+// Each entry in the buffer is an instance of cartesian_dda.
+
+cartesian_dda* cdda[BUFFER_SIZE];
+
+static cartesian_dda cdda0;
+static cartesian_dda cdda1;
+static cartesian_dda cdda2;
+static cartesian_dda cdda3;
+
+volatile byte head;
+volatile byte tail;
+
+unsigned char interruptBlink;
+
+// Where the machine is from the point of view of the command stream
+
+FloatPoint where_i_am;
+
+// Our interrupt function
+
+SIGNAL(SIG_OUTPUT_COMPARE1A)
+{
+ disableTimerInterrupt();
+
+ interruptBlink++;
+ if(interruptBlink & 0x80)
+ digitalWrite(DEBUG_PIN, 1);
+ else
+ digitalWrite(DEBUG_PIN, 0);
+
+ if(cdda[tail]->active())
+ cdda[tail]->dda_step();
+ else
+ dQMove();
+
+ enableTimerInterrupt();
+}
+
+void setup()
+{
+ disableTimerInterrupt();
+ setupTimerInterrupt();
+ interruptBlink = 0;
+ pinMode(DEBUG_PIN, OUTPUT);
+ debugstring[0] = 0;
+
+ ex[0] = &ex0;
+#if EXTRUDER_COUNT == 2
+ ex[1] = &ex1;
+#endif
+ extruder_in_use = 0;
+
+ head = 0;
+ tail = 0;
+
+ cdda[0] = &cdda0;
+ cdda[1] = &cdda1;
+ cdda[2] = &cdda2;
+ cdda[3] = &cdda3;
+
+ //setExtruder();
+
+ init_process_string();
+
+ where_i_am.x = 0.0;
+ where_i_am.y = 0.0;
+ where_i_am.z = 0.0;
+ where_i_am.e = 0.0;
+ where_i_am.f = SLOW_XY_FEEDRATE;
+
+ Serial.begin(HOST_BAUD);
+ Serial.println("start");
+
+#if MOTHERBOARD > 1
+ rs485Interface.begin(RS485_BAUD);
+#endif
+
+ setTimer(DEFAULT_TICK);
+ enableTimerInterrupt();
+}
+
+//long count = 0;
+//int ct1 = 0;
+
+void loop()
+{
+ manageAllExtruders();
+ get_and_do_command();
+#if MOTHERBOARD > 1
+ talker.tick();
+#endif
+/*
+ count++;
+ if(count > 1000)
+ {
+ ct1++;
+ ex[0]->step();
+ if(!ex[0]->ping())
+ {
+ Serial.print(ct1);
+ Serial.println(debugstring);
+ debugstring[0] = 0;
+ }
+ count = 0;
+ }
+*/
+}
+
+//******************************************************************************************
+
+// The move buffer
+
+inline bool qFull()
+{
+ if(tail == 0)
+ return head == (BUFFER_SIZE - 1);
+ else
+ return head == (tail - 1);
+}
+
+inline bool qEmpty()
+{
+ return tail == head && !cdda[tail]->active();
+}
+
+inline void qMove(const FloatPoint& p)
+{
+ while(qFull()) delay(WAITING_DELAY);
+ byte h = head;
+ h++;
+ if(h >= BUFFER_SIZE)
+ h = 0;
+ cdda[h]->set_target(p);
+ head = h;
+}
+
+inline void dQMove()
+{
+ if(qEmpty())
+ return;
+ byte t = tail;
+ t++;
+ if(t >= BUFFER_SIZE)
+ t = 0;
+ cdda[t]->dda_start();
+ tail = t;
+}
+
+inline void setUnits(bool u)
+{
+ for(byte i = 0; i < BUFFER_SIZE; i++)
+ cdda[i]->set_units(u);
+}
+
+
+inline void setPosition(const FloatPoint& p)
+{
+ where_i_am = p;
+}
+
+
+//******************************************************************************************
+
+// Interrupt functions
+
+void setupTimerInterrupt()
+{
+ //clear the registers
+ TCCR1A = 0;
+ TCCR1B = 0;
+ TCCR1C = 0;
+ 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);
+}
+
+void setTimerResolution(byte r)
+{
+ //here's how you figure out the tick size:
+ // 1000000 / ((16000000 / prescaler))
+ // 1000000 = microseconds in 1 second
+ // 16000000 = cycles in 1 second
+ // prescaler = your prescaler
+
+ // no prescaler == 0.0625 usec tick
+ if (r == 0)
+ {
+ // 001 = clk/1
+ TCCR1B &= ~(1<<CS12);
+ TCCR1B &= ~(1<<CS11);
+ TCCR1B |= (1<<CS10);
+ }
+ // prescale of /8 == 0.5 usec tick
+ else if (r == 1)
+ {
+ // 010 = clk/8
+ TCCR1B &= ~(1<<CS12);
+ TCCR1B |= (1<<CS11);
+ TCCR1B &= ~(1<<CS10);
+ }
+ // prescale of /64 == 4 usec tick
+ else if (r == 2)
+ {
+ // 011 = clk/64
+ TCCR1B &= ~(1<<CS12);
+ TCCR1B |= (1<<CS11);
+ TCCR1B |= (1<<CS10);
+ }
+ // prescale of /256 == 16 usec tick
+ else if (r == 3)
+ {
+ // 100 = clk/256
+ TCCR1B |= (1<<CS12);
+ TCCR1B &= ~(1<<CS11);
+ TCCR1B &= ~(1<<CS10);
+ }
+ // prescale of /1024 == 64 usec tick
+ else
+ {
+ // 101 = clk/1024
+ TCCR1B |= (1<<CS12);
+ TCCR1B &= ~(1<<CS11);
+ TCCR1B |= (1<<CS10);
+ }
+}
+
+unsigned int getTimerCeiling(const long& delay)
+{
+ // our slowest speed at our highest resolution ( (2^16-1) * 0.0625 usecs = 4095 usecs)
+ if (delay <= 65535L)
+ return (delay & 0xffff);
+ // our slowest speed at our next highest resolution ( (2^16-1) * 0.5 usecs = 32767 usecs)
+ else if (delay <= 524280L)
+ return ((delay / 8) & 0xffff);
+ // our slowest speed at our medium resolution ( (2^16-1) * 4 usecs = 262140 usecs)
+ else if (delay <= 4194240L)
+ return ((delay / 64) & 0xffff);
+ // our slowest speed at our medium-low resolution ( (2^16-1) * 16 usecs = 1048560 usecs)
+ else if (delay <= 16776960L)
+ return ((delay / 256) & 0xffff);
+ // our slowest speed at our lowest resolution ((2^16-1) * 64 usecs = 4194240 usecs)
+ else if (delay <= 67107840L)
+ return ((delay / 1024) & 0xffff);
+ //its really slow... hopefully we can just get by with super slow.
+ else
+ return 65535;
+}
+
+byte getTimerResolution(const long& delay)
+{
+ // these also represent frequency: 1000000 / delay / 2 = frequency in hz.
+
+ // 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;
+ // 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;
+ // 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;
+ // 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;
+ // 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;
+ //its really slow... hopefully we can just get by with super slow.
+ else
+ return 4;
+}
+
+
+// Depending on how much work the interrupt function has to do, this is
+// pretty accurate between 10 us and 0.1 s. At fast speeds, the time
+// taken in the interrupt function becomes significant, of course.
+
+// Note - it is up to the user to call enableTimerInterrupt() after a call
+// to this function.
+
+inline void setTimer(long delay)
+{
+ // delay is the delay between steps in microsecond ticks.
+ //
+ // we break it into 5 different resolutions based on the delay.
+ // then we set the resolution based on the size of the delay.
+ // we also then calculate the timer ceiling required. (ie what the counter counts to)
+ // the result is the timer counts up to the appropriate time and then fires an interrupt.
+
+ // Actual ticks are 0.0625 us, so multiply delay by 16
+
+ delay <<= 4;
+
+ setTimerCeiling(getTimerCeiling(delay));
+ setTimerResolution(getTimerResolution(delay));
+}
+
+
+void delayMicrosecondsInterruptible(unsigned int us)
+{
+ // for a one-microsecond delay, simply return. the overhead
+ // of the function call yields a delay of approximately 1 1/8 us.
+ if (--us == 0)
+ return;
+
+ // the following loop takes a quarter of a microsecond (4 cycles)
+ // per iteration, so execute it four times for each microsecond of
+ // delay requested.
+ us <<= 2;
+
+ // account for the time taken in the preceeding commands.
+ us -= 2;
+
+ // busy wait
+ __asm__ __volatile__ ("1: sbiw %0,1" "\n\t" // 2 cycles
+"brne 1b" :
+ "=w" (us) :
+ "0" (us) // 2 cycles
+ );
+}
+
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/ThermistorTable.h b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/ThermistorTable.h
new file mode 100755
index 00000000..c55b9c91
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/ThermistorTable.h
@@ -0,0 +1,54 @@
+#ifndef THERMISTORTABLE_H_
+#define THERMISTORTABLE_H_
+
+#if MOTHERBOARD < 2
+
+// Uncomment the next line if you are using a thermistor; leave it if you have a thermocouple
+//#define USE_THERMISTOR
+
+// How many temperature samples to take for an average. each sample takes about 100 usecs.
+#define TEMPERATURE_SAMPLES 3
+
+// How accurately do we maintain the temperature?
+#define HALF_DEAD_ZONE 5
+
+// Thermistor lookup table for RepRap Temperature Sensor Boards (http://make.rrrf.org/ts)
+// See this page:
+// http://dev.www.reprap.org/bin/view/Main/Thermistor
+// for details of what goes in this table.
+// Made with createTemperatureLookup.py (http://svn.reprap.org/trunk/reprap/firmware/Arduino/utilities/createTemperatureLookup.py)
+// ./createTemperatureLookup.py --r0=100000 --t0=25 --r1=0 --r2=4700 --beta=4066 --max-adc=1023
+// r0: 100000
+// t0: 25
+// r1: 0
+// r2: 4700
+// beta: 4066
+// max adc: 1023
+#ifdef USE_THERMISTOR
+#define NUMTEMPS 20
+short temptable[NUMTEMPS][2] = {
+ {1, 841},
+ {54, 255},
+ {107, 209},
+ {160, 184},
+ {213, 166},
+ {266, 153},
+ {319, 142},
+ {372, 132},
+ {425, 124},
+ {478, 116},
+ {531, 108},
+ {584, 101},
+ {637, 93},
+ {690, 86},
+ {743, 78},
+ {796, 70},
+ {849, 61},
+ {902, 50},
+ {955, 34},
+ {1008, 3}
+};
+
+#endif
+#endif
+#endif
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.h b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.h
new file mode 100755
index 00000000..8706a41d
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.h
@@ -0,0 +1,174 @@
+/*
+ * This class controls the movement of the RepRap machine.
+ * It implements a DDA in four dimensions, so the length of extruded
+ * filament is treated as a variable, just like X, Y, and Z.
+ *
+ * Adrian Bowyer 9 May 2009
+ */
+
+#ifndef CARTESIAN_DDA_H
+#define CARTESIAN_DDA_H
+
+// Main class for moving the RepRap machine about
+
+class cartesian_dda
+{
+private:
+
+ //extruder* ext; // The extruder I'm currently using - keep this up to date...
+
+ FloatPoint units; // Factors for converting either mm or inches to steps
+
+ FloatPoint target_position; // Where it's going
+ FloatPoint delta_position; // The difference between the two
+ float distance; // How long the path is
+
+ LongPoint current_steps; // Similar information as above in steps rather than units
+ LongPoint target_steps;
+ LongPoint delta_steps;
+ LongPoint dda_counter; // DDA error-accumulation variables
+ long t_scale; // When doing lots of t steps, scale them so the DDA doesn't spend for ever on them
+
+ byte x_direction; // Am I going in the + or - direction?
+ byte y_direction;
+ byte z_direction;
+ byte e_direction;
+ byte f_direction;
+
+ bool x_can_step; // Am I not at an endstop? Have I not reached the target? etc.
+ bool y_can_step;
+ bool z_can_step;
+ bool e_can_step;
+ bool f_can_step;
+
+// Variables for acceleration calculations
+
+ long total_steps; // The number of steps to take along the longest movement axis
+
+ long timestep; // microseconds
+ bool nullmove; // this move is zero length
+ bool real_move; // Flag to know if we've changed something physical
+ volatile bool live; // Flag for when we're plotting a line
+
+// Internal functions that need not concern the user
+
+ // Take a single step
+
+ void do_x_step();
+ void do_y_step();
+ void do_z_step();
+ void do_e_step();
+
+ // Can this axis step?
+
+ bool can_step(byte min_pin, byte max_pin, long current, long target, byte dir);
+
+ // Read a limit switch
+
+ bool read_switch(byte pin);
+
+ // Work out the number of microseconds between steps
+
+ long calculate_feedrate_delay(const float& feedrate);
+
+ // Switch the steppers on and off
+
+ void enable_steppers();
+ void disable_steppers();
+
+ // Custom short delay function (microseconds)
+
+ //void delayMicrosecondsInterruptible(unsigned int us);
+
+
+public:
+
+ cartesian_dda();
+
+ // Set where I'm going
+
+ void set_target(const FloatPoint& p);
+
+ // Start the DDA
+
+ void dda_start();
+
+ // Do one step of the DDA
+
+ void dda_step();
+
+ // Are we running at the moment?
+
+ bool active();
+
+ // True for mm; false for inches
+
+ void set_units(bool using_mm);
+
+ // Record the selection of a new extruder
+
+ //void set_extruder(extruder* ex);
+};
+
+// Short functions inline to save memory; particularly useful in the Arduino
+
+
+//inline void cartesian_dda::set_extruder(extruder* ex)
+//{
+// ext = ex;
+//}
+
+inline bool cartesian_dda::active()
+{
+ return live;
+}
+
+inline void cartesian_dda::do_x_step()
+{
+ digitalWrite(X_STEP_PIN, HIGH);
+ delayMicrosecondsInterruptible(5);
+ digitalWrite(X_STEP_PIN, LOW);
+}
+
+inline void cartesian_dda::do_y_step()
+{
+ digitalWrite(Y_STEP_PIN, HIGH);
+ delayMicrosecondsInterruptible(5);
+ digitalWrite(Y_STEP_PIN, LOW);
+}
+
+inline void cartesian_dda::do_z_step()
+{
+ digitalWrite(Z_STEP_PIN, HIGH);
+ delayMicrosecondsInterruptible(5);
+ digitalWrite(Z_STEP_PIN, LOW);
+}
+
+inline void cartesian_dda::do_e_step()
+{
+ ex[extruder_in_use]->sStep();
+}
+
+inline long cartesian_dda::calculate_feedrate_delay(const float& feedrate)
+{
+
+ // Calculate delay between steps in microseconds. Here it is in English:
+ // (feedrate is in mm/minute, distance is in mm)
+ // 60000000.0*distance/feedrate = move duration in microseconds
+ // move duration/total_steps = time between steps for master axis.
+
+ return round( (distance*60000000.0) / (feedrate*(float)total_steps) );
+}
+
+inline bool cartesian_dda::read_switch(byte pin)
+{
+ //dual read as crude debounce
+
+ #if ENDSTOPS_INVERTING == 1
+ return !digitalRead(pin) && !digitalRead(pin);
+ #else
+ return digitalRead(pin) && digitalRead(pin);
+ #endif
+}
+
+#endif
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.pde b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.pde
new file mode 100755
index 00000000..927ddc16
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/cartesian_dda.pde
@@ -0,0 +1,423 @@
+#include <stdio.h>
+#include "configuration.h"
+#include "pins.h"
+#include "extruder.h"
+#include "vectors.h"
+#include "cartesian_dda.h"
+
+
+// Initialise X, Y and Z. The extruder is initialized
+// separately.
+
+cartesian_dda::cartesian_dda()
+{
+ live = false;
+ nullmove = false;
+
+ // Default is going forward
+
+ x_direction = 1;
+ y_direction = 1;
+ z_direction = 1;
+ e_direction = 1;
+ f_direction = 1;
+
+ // Default to the origin and not going anywhere
+
+ target_position.x = 0.0;
+ target_position.y = 0.0;
+ target_position.z = 0.0;
+ target_position.e = 0.0;
+ target_position.f = SLOW_XY_FEEDRATE;
+
+ // Set up the pin directions
+
+ pinMode(X_STEP_PIN, OUTPUT);
+ pinMode(X_DIR_PIN, OUTPUT);
+
+ pinMode(Y_STEP_PIN, OUTPUT);
+ pinMode(Y_DIR_PIN, OUTPUT);
+
+ pinMode(Z_STEP_PIN, OUTPUT);
+ pinMode(Z_DIR_PIN, OUTPUT);
+
+#if MOTHERBOARD > 0
+ pinMode(X_ENABLE_PIN, OUTPUT);
+ pinMode(Y_ENABLE_PIN, OUTPUT);
+ pinMode(Z_ENABLE_PIN, OUTPUT);
+#endif
+
+ //turn the motors off at the start.
+
+ disable_steppers();
+
+#if ENDSTOPS_MIN_ENABLED == 1
+ pinMode(X_MIN_PIN, INPUT);
+ pinMode(Y_MIN_PIN, INPUT);
+ pinMode(Z_MIN_PIN, INPUT);
+#endif
+
+#if ENDSTOPS_MAX_ENABLED == 1
+ pinMode(X_MAX_PIN, INPUT);
+ pinMode(Y_MAX_PIN, INPUT);
+ pinMode(Z_MAX_PIN, INPUT);
+#endif
+
+ // Default units are mm
+
+ set_units(true);
+}
+
+// Switch between mm and inches
+
+void cartesian_dda::set_units(bool using_mm)
+{
+ if(using_mm)
+ {
+ units.x = X_STEPS_PER_MM;
+ units.y = Y_STEPS_PER_MM;
+ units.z = Z_STEPS_PER_MM;
+ units.e = E_STEPS_PER_MM;
+ units.f = 1.0;
+ } else
+ {
+ units.x = X_STEPS_PER_INCH;
+ units.y = Y_STEPS_PER_INCH;
+ units.z = Z_STEPS_PER_INCH;
+ units.e = E_STEPS_PER_INCH;
+ units.f = 1.0;
+ }
+}
+
+
+void cartesian_dda::set_target(const FloatPoint& p)
+{
+ target_position = p;
+ nullmove = false;
+
+ //figure our deltas.
+
+ delta_position = fabsv(target_position - where_i_am);
+
+ // The feedrate values refer to distance in (X, Y, Z) space, so ignore e and f
+ // values unless they're the only thing there.
+
+ FloatPoint squares = delta_position*delta_position;
+ distance = squares.x + squares.y + squares.z;
+ // If we are 0, only thing changing is e
+ if(distance <= 0.0)
+ distance = squares.e;
+ // If we are still 0, only thing changing is f
+ if(distance <= 0.0)
+ distance = squares.f;
+ distance = sqrt(distance);
+
+ //set our steps current, target, and delta
+
+ current_steps = to_steps(units, where_i_am);
+ target_steps = to_steps(units, target_position);
+ delta_steps = absv(target_steps - current_steps);
+
+ // find the dominant axis.
+ // NB we ignore the f values here, as it takes no time to take a step in time :-)
+
+ total_steps = max(delta_steps.x, delta_steps.y);
+ total_steps = max(total_steps, delta_steps.z);
+ total_steps = max(total_steps, delta_steps.e);
+
+ // If we're not going anywhere, flag the fact
+
+ if(total_steps == 0)
+ {
+ nullmove = true;
+ where_i_am = p;
+ return;
+ }
+
+#ifndef ACCELERATION_ON
+ current_steps.f = round(target_position.f);
+#endif
+
+ delta_steps.f = abs(target_steps.f - current_steps.f);
+
+ // Rescale the feedrate so it doesn't take lots of steps to do
+
+ t_scale = 1;
+ if(delta_steps.f > total_steps)
+ {
+ t_scale = delta_steps.f/total_steps;
+ if(t_scale >= 3)
+ {
+ target_steps.f = target_steps.f/t_scale;
+ current_steps.f = current_steps.f/t_scale;
+ delta_steps.f = abs(target_steps.f - current_steps.f);
+ if(delta_steps.f > total_steps)
+ total_steps = delta_steps.f;
+ } else
+ {
+ t_scale = 1;
+ total_steps = delta_steps.f;
+ }
+ }
+
+ //what is our direction?
+
+ x_direction = (target_position.x >= where_i_am.x);
+ y_direction = (target_position.y >= where_i_am.y);
+ z_direction = (target_position.z >= where_i_am.z);
+ e_direction = (target_position.e >= where_i_am.e);
+ f_direction = (target_position.f >= where_i_am.f);
+
+ dda_counter.x = -total_steps/2;
+ dda_counter.y = dda_counter.x;
+ dda_counter.z = dda_counter.x;
+ dda_counter.e = dda_counter.x;
+ dda_counter.f = dda_counter.x;
+
+ where_i_am = p;
+
+ return;
+}
+
+
+
+void cartesian_dda::dda_step()
+{
+ if(!live)
+ return;
+
+ do
+ {
+ x_can_step = can_step(X_MIN_PIN, X_MAX_PIN, current_steps.x, target_steps.x, x_direction);
+ y_can_step = can_step(Y_MIN_PIN, Y_MAX_PIN, current_steps.y, target_steps.y, y_direction);
+ z_can_step = can_step(Z_MIN_PIN, Z_MAX_PIN, current_steps.z, target_steps.z, z_direction);
+ e_can_step = can_step(-1, -1, current_steps.e, target_steps.e, e_direction);
+ f_can_step = can_step(-1, -1, current_steps.f, target_steps.f, f_direction);
+
+ real_move = false;
+
+ if (x_can_step)
+ {
+ dda_counter.x += delta_steps.x;
+
+ if (dda_counter.x > 0)
+ {
+ do_x_step();
+ real_move = true;
+ dda_counter.x -= total_steps;
+
+ if (x_direction)
+ current_steps.x++;
+ else
+ current_steps.x--;
+ }
+ }
+
+ if (y_can_step)
+ {
+ dda_counter.y += delta_steps.y;
+
+ if (dda_counter.y > 0)
+ {
+ do_y_step();
+ real_move = true;
+ dda_counter.y -= total_steps;
+
+ if (y_direction)
+ current_steps.y++;
+ else
+ current_steps.y--;
+ }
+ }
+
+ if (z_can_step)
+ {
+ dda_counter.z += delta_steps.z;
+
+ if (dda_counter.z > 0)
+ {
+ do_z_step();
+ real_move = true;
+ dda_counter.z -= total_steps;
+
+ if (z_direction)
+ current_steps.z++;
+ else
+ current_steps.z--;
+ }
+ }
+
+ if (e_can_step)
+ {
+ dda_counter.e += delta_steps.e;
+
+ if (dda_counter.e > 0)
+ {
+ do_e_step();
+ real_move = true;
+ dda_counter.e -= total_steps;
+
+ if (e_direction)
+ current_steps.e++;
+ else
+ current_steps.e--;
+ }
+ }
+
+ if (f_can_step)
+ {
+ dda_counter.f += delta_steps.f;
+
+ if (dda_counter.f > 0)
+ {
+ dda_counter.f -= total_steps;
+ if (f_direction)
+ current_steps.f++;
+ else
+ current_steps.f--;
+ }
+ }
+
+
+ // wait for next step.
+ // Use milli- or micro-seconds, as appropriate
+ // If the only thing that changed was f keep looping
+
+ if(real_move)
+ {
+ if(t_scale > 1)
+ timestep = t_scale*current_steps.f;
+ else
+ timestep = current_steps.f;
+ timestep = calculate_feedrate_delay((float) timestep);
+ setTimer(timestep);
+ }
+ } while (!real_move && f_can_step);
+
+ live = (x_can_step || y_can_step || z_can_step || e_can_step || f_can_step);
+
+// Wrap up at the end of a line
+
+ if(!live)
+ {
+ disable_steppers();
+ setTimer(DEFAULT_TICK);
+ }
+
+}
+
+
+// Run the DDA
+
+void cartesian_dda::dda_start()
+{
+ // Set up the DDA
+ //sprintf(debugstring, "%d %d", x_direction, nullmove);
+
+ if(nullmove)
+ return;
+
+ //set our direction pins as well
+#if INVERT_X_DIR == 1
+ digitalWrite(X_DIR_PIN, !x_direction);
+#else
+ digitalWrite(X_DIR_PIN, x_direction);
+#endif
+
+#if INVERT_Y_DIR == 1
+ digitalWrite(Y_DIR_PIN, !y_direction);
+#else
+ digitalWrite(Y_DIR_PIN, y_direction);
+#endif
+
+#if INVERT_Z_DIR == 1
+ digitalWrite(Z_DIR_PIN, !z_direction);
+#else
+ digitalWrite(Z_DIR_PIN, z_direction);
+#endif
+ if(e_direction)
+ ex[extruder_in_use]->setDirection(1);
+ else
+ ex[extruder_in_use]->setDirection(0);
+
+ //turn on steppers to start moving =)
+
+ enable_steppers();
+
+ // extcount = 0;
+
+ setTimer(DEFAULT_TICK);
+ live = true;
+}
+
+
+bool cartesian_dda::can_step(byte min_pin, byte max_pin, long current, long target, byte dir)
+{
+
+ //stop us if we're on target
+
+ if (target == current)
+ return false;
+
+#if ENDSTOPS_MIN_ENABLED == 1
+
+ //stop us if we're home and still going
+
+ else if(min_pin >= 0)
+ {
+ if (read_switch(min_pin) && !dir)
+ return false;
+ }
+#endif
+
+#if ENDSTOPS_MAX_ENABLED == 1
+
+ //stop us if we're at max and still going
+
+ else if(max_pin >= 0)
+ {
+ if (read_switch(max_pin) && dir)
+ return false;
+ }
+#endif
+
+ // All OK - we can step
+
+ return true;
+}
+
+
+void cartesian_dda::enable_steppers()
+{
+#if MOTHERBOARD > 0
+ if(delta_steps.x)
+ digitalWrite(X_ENABLE_PIN, ENABLE_ON);
+ if(delta_steps.y)
+ digitalWrite(Y_ENABLE_PIN, ENABLE_ON);
+ if(delta_steps.z)
+ digitalWrite(Z_ENABLE_PIN, ENABLE_ON);
+ if(delta_steps.e)
+ ex[extruder_in_use]->enableStep();
+#endif
+}
+
+
+
+void cartesian_dda::disable_steppers()
+{
+#if MOTHERBOARD > 0
+ //disable our steppers
+#if DISABLE_X
+ digitalWrite(X_ENABLE_PIN, !ENABLE_ON);
+#endif
+#if DISABLE_Y
+ digitalWrite(Y_ENABLE_PIN, !ENABLE_ON);
+#endif
+#if DISABLE_Z
+ digitalWrite(Z_ENABLE_PIN, !ENABLE_ON);
+#endif
+ ex[extruder_in_use]->disableStep();
+#endif
+}
+
+
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/configuration.h.dist b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/configuration.h.dist
new file mode 100755
index 00000000..6045d22c
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/configuration.h.dist
@@ -0,0 +1,184 @@
+#ifndef PARAMETERS_H
+#define PARAMETERS_H
+
+// Here are the moterboard codes; set MOTHERBOARD to the right one
+// (Arduino: 0 - no longer in use)
+// Sanguino or RepRap Motherboard with direct drive extruders: 1
+// RepRap Motherboard with RS485 extruders: 2
+// Arduino Mega: 3
+
+#define MOTHERBOARD 2
+
+// Comment out the next line if you are running a Darwin
+
+#define MENDEL 1
+
+// The speed at which to talk with the host computer
+
+#define HOST_BAUD 19200
+
+// Set 1s where you have endstops; 0s where you don't
+#define ENDSTOPS_MIN_ENABLED 1
+#define ENDSTOPS_MAX_ENABLED 0
+
+#define INCHES_TO_MM 25.4
+
+#ifdef MENDEL
+
+#if 0
+// define the XYZ parameters of Mendel
+
+#define X_STEPS_PER_MM 10.047
+#define X_STEPS_PER_INCH (X_STEPS_PER_MM*INCHES_TO_MM)
+#define X_MOTOR_STEPS 400
+#define INVERT_X_DIR 0
+
+#define Y_STEPS_PER_MM 10.047
+#define Y_STEPS_PER_INCH (Y_STEPS_PER_MM*INCHES_TO_MM)
+#define Y_MOTOR_STEPS 400
+#define INVERT_Y_DIR 0
+
+#define Z_STEPS_PER_MM 563.877
+#define Z_STEPS_PER_INCH (Z_STEPS_PER_MM*INCHES_TO_MM)
+#define Z_MOTOR_STEPS 400
+#define INVERT_Z_DIR 0
+
+#else
+// parameters for the Bath U. mendel prototype
+#define X_STEPS_PER_MM 13.333333
+#define X_STEPS_PER_INCH (X_STEPS_PER_MM*INCHES_TO_MM)
+#define X_MOTOR_STEPS 400
+#define INVERT_X_DIR 0
+
+#define Y_STEPS_PER_MM 13.333333
+#define Y_STEPS_PER_INCH (Y_STEPS_PER_MM*INCHES_TO_MM)
+#define Y_MOTOR_STEPS 400
+#define INVERT_Y_DIR 0
+
+#define Z_STEPS_PER_MM 938.64
+#define Z_STEPS_PER_INCH (Z_STEPS_PER_MM*INCHES_TO_MM)
+#define Z_MOTOR_STEPS 400
+#define INVERT_Z_DIR 0
+
+#endif
+
+
+#else
+
+// This is for Darwin.
+
+#define X_STEPS_PER_MM 7.99735
+#define X_STEPS_PER_INCH (X_STEPS_PER_MM*INCHES_TO_MM)
+#define X_MOTOR_STEPS 400
+#define INVERT_X_DIR 0
+
+#define Y_STEPS_PER_MM 7.99735
+#define Y_STEPS_PER_INCH (Y_STEPS_PER_MM*INCHES_TO_MM)
+#define Y_MOTOR_STEPS 400
+#define INVERT_Y_DIR 0
+
+#define Z_STEPS_PER_MM 320
+#define Z_STEPS_PER_INCH (Z_STEPS_PER_MM*INCHES_TO_MM)
+#define Z_MOTOR_STEPS 400
+#define INVERT_Z_DIR 0
+
+
+#endif
+
+// For when we have a stepper-driven extruder
+// E_STEPS_PER_MM is the number of steps needed to
+// extrude 1mm out of the nozzle.
+
+#define E_STEPS_PER_MM 0.706 // NEMA 17 extruder 5mm diameter drive - empirically adjusted
+//#define E_STEPS_PER_MM 2.2 // NEMA 14 geared extruder 8mm diameter drive
+#define E_STEPS_PER_INCH (E_STEPS_PER_MM*INCHES_TO_MM)
+#define E_MOTOR_STEPS 400
+
+//our maximum feedrates
+#define FAST_XY_FEEDRATE 3000.0
+#define FAST_Z_FEEDRATE 50.0
+
+// Data for acceleration calculations
+// Comment out the next line to turn accelerations off
+#define ACCELERATION_ON
+#define SLOW_XY_FEEDRATE 1000.0 // Speed from which to start accelerating
+#define SLOW_Z_FEEDRATE 20
+
+// Set to 1 if enable pins are inverting
+// For RepRap stepper boards version 1.x the enable pins are *not* inverting.
+// For RepRap stepper boards version 2.x and above the enable pins are inverting.
+#define INVERT_ENABLE_PINS 1
+
+#if INVERT_ENABLE_PINS == 1
+#define ENABLE_ON LOW
+#else
+#define ENABLE_ON HIGH
+#endif
+
+// Set these to 1 to disable an axis when it's not being used,
+// and for the extruder
+
+#define DISABLE_X 0
+#define DISABLE_Y 0
+#define DISABLE_Z 1
+#define DISABLE_E 0
+
+// Set to one if sensor outputs inverting (ie: 1 means open, 0 means closed)
+// RepRap opto endstops with H21LOI sensors are not inverting; ones with H21LOB
+// are inverting
+
+#define ENDSTOPS_INVERTING 1
+
+//our command string length
+#define COMMAND_SIZE 128
+
+// The size of the movement buffer
+
+#define BUFFER_SIZE 4
+
+// Number of microseconds between timer interrupts when no movement
+// is happening
+
+#define DEFAULT_TICK (long)1000
+
+// What delay() value to use when waiting for things to free up in milliseconds
+
+#define WAITING_DELAY 1
+
+#if MOTHERBOARD > 1
+
+#define MY_NAME 'H' // Byte representing the name of this device
+#define E0_NAME '0' // Byte representing the name of extruder 0
+#define E1_NAME '1' // Byte representing the name of extruder 1
+
+#define RS485_MASTER 1 // Set 0 for the slave
+
+#endif
+
+extern char debugstring[];
+
+void delayMicrosecondsInterruptible(unsigned int us);
+
+// Inline interrupt control functions
+
+inline void enableTimerInterrupt()
+{
+ TIMSK1 |= (1<<OCIE1A);
+}
+
+inline void disableTimerInterrupt()
+{
+ TIMSK1 &= ~(1<<OCIE1A);
+}
+
+inline void setTimerCeiling(unsigned int c)
+{
+ OCR1A = c;
+}
+
+inline void resetTimer()
+{
+ TCNT2 = 0;
+}
+
+#endif
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.h b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.h
new file mode 100755
index 00000000..24084348
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.h
@@ -0,0 +1,321 @@
+
+// Class for controlling each extruder
+//
+// Adrian Bowyer 14 May 2009
+
+#ifndef EXTRUDER_H
+#define EXTRUDER_H
+
+#define EXTRUDER_COUNT 1
+
+void manageAllExtruders();
+
+void newExtruder(byte e);
+
+/**********************************************************************************************
+
+* Sanguino/RepRap Motherboard v 1.0
+
+*/
+
+#if MOTHERBOARD < 2
+
+#define EXTRUDER_FORWARD true
+#define EXTRUDER_REVERSE false
+
+class extruder
+{
+
+
+public:
+
+ extruder(byte md_pin, byte ms_pin, byte h_pin, byte f_pin, byte t_pin, byte vd_pin, byte ve_pin, byte se_pin);
+ void waitForTemperature();
+ void valveSet(bool open, int dTime);
+ void setDirection(bool direction);
+// void set_speed(float es);
+ void setCooler(byte e_speed);
+ void setTemperature(int temp);
+ int getTemperature();
+ void manage();
+// Interrupt setup and handling functions for stepper-driven extruders
+
+// void interrupt();
+ void sStep();
+
+ void enableStep();
+ void disableStep();
+
+private:
+
+//these our the default values for the extruder.
+ byte e_speed;
+ int target_celsius;
+ int max_celsius;
+ byte heater_low;
+ byte heater_high;
+ byte heater_current;
+ int extrude_step_count;
+
+// These are used for temperature control
+ byte count ;
+ int oldT, newT;
+
+//this is for doing encoder based extruder control
+// int rpm;
+// long e_delay;
+// int error;
+// int last_extruder_error;
+// int error_delta;
+ bool e_direction;
+ bool valve_open;
+
+// The pins we control
+ byte motor_dir_pin, motor_speed_pin, heater_pin, fan_pin, temp_pin, valve_dir_pin, valve_en_pin, step_en_pin;
+
+ byte wait_till_hot();
+ //byte wait_till_cool();
+ void temperatureError();
+ int sampleTemperature();
+
+};
+
+inline void extruder::enableStep()
+{
+ if(step_en_pin < 0)
+ return;
+ digitalWrite(step_en_pin, ENABLE_ON);
+}
+
+inline void extruder::disableStep()
+{
+ if(step_en_pin < 0)
+ return;
+#if DISABLE_E
+ digitalWrite(step_en_pin, !ENABLE_ON);
+#endif
+}
+
+inline void extruder::sStep()
+{
+ digitalWrite(motor_speed_pin, HIGH);
+ delayMicrosecondsInterruptible(5);
+ digitalWrite(motor_speed_pin, LOW);
+}
+
+inline void extruder::temperatureError()
+{
+ Serial.print("E: ");
+ Serial.println(getTemperature());
+}
+
+
+inline void extruder::setDirection(bool dir)
+{
+ e_direction = dir;
+ digitalWrite(motor_dir_pin, e_direction);
+}
+
+inline void extruder::setCooler(byte sp)
+{
+ if(step_en_pin >= 0) // Step enable conflicts with the fan
+ return;
+ analogWrite(fan_pin, sp);
+}
+
+/**********************************************************************************************
+
+* RepRap Motherboard v 1.x (x >= 1)
+* Extruder is now on RS485
+
+*/
+
+#else
+
+
+#define WAIT_T 'W' // wait_for_temperature();
+#define VALVE 'V' // valve_set(bool open, int dTime);
+#define DIRECTION 'D' // set_direction(bool direction);
+#define COOL 'C' // set_cooler(byte e_speed);
+#define SET_T 'T' // set_temperature(int temp);
+#define GET_T 't' // get_temperature();
+#define STEP 'S' // step();
+#define ENABLE 'E' // enableStep();
+#define DISABLE 'e' // disableStep();
+#define PREAD 'R' // read the pot voltage
+#define SPWM 'M' // Set the motor PWM
+#define PING 'P' // Just acknowledge
+
+class extruder
+{
+
+public:
+ extruder(char name);
+ void waitForTemperature();
+ void valveSet(bool open, int dTime);
+ void setDirection(bool direction);
+ void setCooler(byte e_speed);
+ void setTemperature(int temp);
+ int getTemperature();
+ void manage();
+ void sStep();
+ void enableStep();
+ void disableStep();
+ int potVoltage();
+ void setPWM(int p);
+ bool ping();
+
+private:
+
+ char my_name;
+ char commandBuffer[RS485_BUF_LEN];
+ char* reply;
+ bool stp;
+
+ void buildCommand(char c);
+ void buildCommand(char c, char v);
+ void buildNumberCommand(char c, int v);
+};
+
+inline extruder::extruder(char name)
+{
+ my_name = name;
+// int v = potVoltage();
+// strcpy(debugstring, reply);
+// setPWM(v);
+ pinMode(E_STEP_PIN, OUTPUT);
+ pinMode(E_DIR_PIN, OUTPUT);
+ digitalWrite(E_STEP_PIN, 0);
+ digitalWrite(E_DIR_PIN, 0);
+ stp = false;
+}
+
+inline void extruder::buildCommand(char c)
+{
+ commandBuffer[0] = c;
+ commandBuffer[1] = 0;
+}
+
+inline void extruder::buildCommand(char c, char v)
+{
+ commandBuffer[0] = c;
+ commandBuffer[1] = v;
+ commandBuffer[2] = 0;
+}
+
+inline void extruder::buildNumberCommand(char c, int v)
+{
+ commandBuffer[0] = c;
+ itoa(v, &commandBuffer[1], 10);
+}
+
+
+inline void extruder::waitForTemperature()
+{
+
+}
+
+inline void extruder::valveSet(bool open, int dTime)
+{
+ if(open)
+ buildCommand(VALVE, '1');
+ else
+ buildCommand(VALVE, '0');
+ talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+
+ delay(dTime);
+}
+
+inline void extruder::setCooler(byte e_speed)
+{
+ buildNumberCommand(COOL, e_speed);
+ talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+}
+
+inline void extruder::setTemperature(int temp)
+{
+ buildNumberCommand(SET_T, temp);
+ talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+}
+
+inline int extruder::getTemperature()
+{
+ buildCommand(GET_T);
+ char* reply = talker.sendPacketAndGetReply(my_name, commandBuffer);
+ return(atoi(reply));
+ //return 10;
+}
+
+inline void extruder::manage()
+{
+
+}
+
+inline void extruder::setDirection(bool direction)
+{
+// if(direction)
+// buildCommand(DIRECTION, '1');
+// else
+// buildCommand(DIRECTION, '0');
+// talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+ if(direction)
+ digitalWrite(E_DIR_PIN, 1);
+ else
+ digitalWrite(E_DIR_PIN, 0);
+}
+
+
+inline void extruder::sStep()
+{
+ //buildCommand(STEP);
+ //talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+ stp = !stp;
+ if(stp)
+ digitalWrite(E_STEP_PIN, 1);
+ else
+ digitalWrite(E_STEP_PIN, 0);
+}
+
+inline void extruder::enableStep()
+{
+ // Not needed
+ /*
+ buildCommand(ENABLE);
+ talker.sendPacketAndGetReply(my_name, commandBuffer);
+ */
+}
+
+inline void extruder::disableStep()
+{
+ // Disabling the extrude stepper causes the backpressure to
+ // turn the motor the wrong way. Leave it on.
+
+ //buildCommand(DISABLE);
+ //talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+}
+
+inline int extruder::potVoltage()
+{
+ buildCommand(PREAD);
+ char* reply = talker.sendPacketAndGetReply(my_name, commandBuffer);
+ return(atoi(reply));
+}
+
+inline void extruder::setPWM(int p)
+{
+ buildNumberCommand(SPWM, p);
+ talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+}
+
+inline bool extruder::ping()
+{
+ buildCommand(PING);
+ return talker.sendPacketAndCheckAcknowledgement(my_name, commandBuffer);
+}
+
+#endif
+
+extern extruder* ex[ ];
+extern byte extruder_in_use;
+
+#endif
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.pde b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.pde
new file mode 100755
index 00000000..564ac321
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/extruder.pde
@@ -0,0 +1,313 @@
+
+
+#include "configuration.h"
+#include "pins.h"
+#include "ThermistorTable.h"
+#include "intercom.h"
+#include "extruder.h"
+
+// Keep all extruders up to temperature etc.
+
+
+void manageAllExtruders()
+{
+ for(byte i = 0; i < EXTRUDER_COUNT; i++)
+ ex[i]->manage();
+}
+
+// Select a new extruder
+
+void newExtruder(byte e)
+{
+ if(e < 0)
+ e = 0;
+ if(e >= EXTRUDER_COUNT)
+ e = EXTRUDER_COUNT - 1;
+
+ if(e != extruder_in_use)
+ {
+ extruder_in_use = e;
+ //setExtruder();
+ }
+}
+
+/***************************************************************************************************************************
+
+If we have a new motherboard (V 1.x, x >= 1), the extruder is entirely controlled via the RS485, and all the functions to do
+it are simple inlines in extruder.h
+
+Otherwise, we have to do the work ourselves...
+*/
+
+#if MOTHERBOARD < 2
+extruder::extruder(byte md_pin, byte ms_pin, byte h_pin, byte f_pin, byte t_pin, byte vd_pin, byte ve_pin, byte se_pin)
+{
+ motor_dir_pin = md_pin;
+ motor_speed_pin = ms_pin;
+ heater_pin = h_pin;
+ fan_pin = f_pin;
+ temp_pin = t_pin;
+ valve_dir_pin = vd_pin;
+ valve_en_pin = ve_pin;
+ step_en_pin = se_pin;
+
+ //setup our pins
+ pinMode(motor_dir_pin, OUTPUT);
+ pinMode(motor_speed_pin, OUTPUT);
+ pinMode(heater_pin, OUTPUT);
+
+ pinMode(temp_pin, INPUT);
+ pinMode(valve_dir_pin, OUTPUT);
+ pinMode(valve_en_pin, OUTPUT);
+
+ //initialize values
+ digitalWrite(motor_dir_pin, EXTRUDER_FORWARD);
+
+ analogWrite(heater_pin, 0);
+ analogWrite(motor_speed_pin, 0);
+ digitalWrite(valve_dir_pin, false);
+ digitalWrite(valve_en_pin, 0);
+
+// The step enable pin and the fan pin are the same...
+// We can have one, or the other, but not both
+
+ if(step_en_pin >= 0)
+ {
+ pinMode(step_en_pin, OUTPUT);
+ disableStep();
+ } else
+ {
+ pinMode(fan_pin, OUTPUT);
+ analogWrite(fan_pin, 0);
+ }
+
+ //these our the default values for the extruder.
+ e_speed = 0;
+ target_celsius = 0;
+ max_celsius = 0;
+ heater_low = 64;
+ heater_high = 255;
+ heater_current = 0;
+ valve_open = false;
+
+//this is for doing encoder based extruder control
+// rpm = 0;
+// e_delay = 0;
+// error = 0;
+// last_extruder_error = 0;
+// error_delta = 0;
+ e_direction = EXTRUDER_FORWARD;
+
+ //default to cool
+ setTemperature(target_celsius);
+}
+
+
+void extruder::waitForTemperature()
+{
+ count = 0;
+ oldT = getTemperature();
+ while (getTemperature() < target_celsius - HALF_DEAD_ZONE)
+ {
+ manageAllExtruders();
+ count++;
+ if(count > 20)
+ {
+ newT = getTemperature();
+ if(newT > oldT)
+ oldT = newT;
+ else
+ {
+ temperatureError();
+ return;
+ }
+ count = 0;
+ }
+ delay(1000);
+ }
+}
+
+/*
+byte extruder::wait_till_cool()
+{
+ count = 0;
+ oldT = get_temperature();
+ while (get_temperature() > target_celsius + HALF_DEAD_ZONE)
+ {
+ manage_all_extruders();
+ count++;
+ if(count > 20)
+ {
+ newT = get_temperature();
+ if(newT < oldT)
+ oldT = newT;
+ else
+ return 1;
+ count = 0;
+ }
+ delay(1000);
+ }
+ return 0;
+}
+*/
+
+
+
+void extruder::valveSet(bool open, int dTime)
+{
+ waitForTemperature();
+ valve_open = open;
+ digitalWrite(valve_dir_pin, open);
+ digitalWrite(valve_en_pin, 1);
+ delay(dTime);
+ digitalWrite(valve_en_pin, 0);
+}
+
+
+void extruder::setTemperature(int temp)
+{
+ target_celsius = temp;
+ max_celsius = (temp*11)/10;
+
+ // If we've turned the heat off, we might as well disable the extrude stepper
+ // if(target_celsius < 1)
+ // disableStep();
+}
+
+/**
+* Samples the temperature and converts it to degrees celsius.
+* Returns degrees celsius.
+*/
+int extruder::getTemperature()
+{
+#ifdef USE_THERMISTOR
+ int raw = sample_temperature(temp_pin);
+
+ int celsius = 0;
+ byte i;
+
+ for (i=1; i<NUMTEMPS; i++)
+ {
+ if (temptable[i][0] > raw)
+ {
+ celsius = temptable[i-1][1] +
+ (raw - temptable[i-1][0]) *
+ (temptable[i][1] - temptable[i-1][1]) /
+ (temptable[i][0] - temptable[i-1][0]);
+
+ break;
+ }
+ }
+
+ // Overflow: Set to last value in the table
+ if (i == NUMTEMPS) celsius = temptable[i-1][1];
+ // Clamp to byte
+ if (celsius > 255) celsius = 255;
+ else if (celsius < 0) celsius = 0;
+
+ return celsius;
+#else
+ return ( 5.0 * sampleTemperature() * 100.0) / 1024.0;
+#endif
+}
+
+
+
+/*
+* This function gives us an averaged sample of the analog temperature pin.
+*/
+int extruder::sampleTemperature()
+{
+ int raw = 0;
+
+ //read in a certain number of samples
+ for (byte i=0; i<TEMPERATURE_SAMPLES; i++)
+ raw += analogRead(temp_pin);
+
+ //average the samples
+ raw = raw/TEMPERATURE_SAMPLES;
+
+ //send it back.
+ return raw;
+}
+
+/*!
+ Manages extruder functions to keep temps, speeds etc
+ at the set levels. Should be called only by manage_all_extruders(),
+ which should be called in all non-trivial loops.
+ o If temp is too low, don't start the motor
+ o Adjust the heater power to keep the temperature at the target
+ */
+void extruder::manage()
+{
+ //make sure we know what our temp is.
+ int current_celsius = getTemperature();
+ byte newheat = 0;
+
+ //put the heater into high mode if we're not at our target.
+ if (current_celsius < target_celsius)
+ newheat = heater_high;
+ //put the heater on low if we're at our target.
+ else if (current_celsius < max_celsius)
+ newheat = heater_low;
+
+ // Only update heat if it changed
+ if (heater_current != newheat) {
+ heater_current = newheat;
+ analogWrite(heater_pin, heater_current);
+ }
+}
+
+
+#if 0
+void extruder::setSpeed(float sp)
+{
+ // DC motor?
+ if(step_en_pin < 0)
+ {
+ e_speed = (byte)sp;
+ if(e_speed > 0)
+ waitForTemperature();
+ analogWrite(motor_speed_pin, e_speed);
+ return;
+ }
+
+ // No - stepper
+ disableTimerInterrupt();
+
+ if(sp <= 1.0e-4)
+ {
+ disableStep();
+ e_speed = 0; // Just use this as a flag
+ return;
+ } else
+ {
+ waitForTemperature();
+ enableStep();
+ e_speed = 1;
+ }
+
+ extrude_step_count = 0;
+
+ float milliseconds_per_step = 60000.0/(E_STEPS_PER_MM*sp);
+ long thousand_ticks_per_step = 4*(long)(milliseconds_per_step);
+ setupTimerInterrupt();
+ setTimer(thousand_ticks_per_step);
+ enableTimerInterrupt();
+}
+
+void extruder::interrupt()
+{
+ if(!e_speed)
+ return;
+ extrude_step_count++;
+ if(extrude_step_count > 1000)
+ {
+ step();
+ extrude_step_count = 0;
+ }
+}
+
+#endif
+#endif
+
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.h b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.h
new file mode 100755
index 00000000..794b5610
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.h
@@ -0,0 +1,241 @@
+/*
+ * Class to handle internal communications in the machine via RS485
+ *
+ * Adrian Bowyer 3 July 2009
+ *
+ */
+
+ /*
+
+ A data packet looks like this:
+
+ * * T F S A d a t a $
+
+ 0 1 2 3 4 . . .
+
+ All these are printable characters. * is the start character; it is not included in the string that is the result of
+ reading the packet. There may be more than one to allow the comms to stabilise. T (to) is the one-char name of the destination,
+ F (from) is the one-char name of the source, d a t a is a char string containing the message. The checksum is S; this is
+ calculated by adding all the bytes of the message (T F A and data, but not itself nor the start and end characters), taking the last four bits
+ of the count, and adding that to the '0' character. A is either RS485_ACK or RS485_ERROR. The packet is terminated by a single $ character. The total length of
+ a packet with all of that should not exceed RS485_BUF_LEN (defined in configuration.h) characters. When a packet is received
+ the $ character is replaced by 0, thus forming a standard C string.
+
+ Error returns: bool functions return true for success, false for failure.
+
+ */
+
+#ifndef INTERCOM_H
+#define INTERCOM_H
+
+#if MOTHERBOARD > 1
+
+// Locations in a packet
+
+#define P_TO 0
+#define P_FROM 1
+#define P_SUM 2
+#define P_ACK 3
+#define P_DATA 4
+
+// Our RS485 driver and timeout
+
+#if RS485_MASTER == 1
+ #define rs485Interface Serial1
+ #define TIMEOUT 3
+#else
+ #define rs485Interface Serial
+ #define TIMEOUT (64*3) // 3 ms, but TIMER0 has been messed with in the slave
+#endif
+
+// Communication speed
+
+//#define RS485_BAUD 115200
+#define RS485_BAUD 1000000
+
+// The acknowledge, start, end, error and checksum characters
+
+#define RS485_ACK 'A'
+#define RS485_START '*'
+#define RS485_END '$'
+#define RS485_ERROR '!'
+#define RS485_CHECK '0'
+
+#define RS485_START_BYTES 3 // The number of start characters to send at the beginning of a packet
+#define RS485_STABILISE 5 // Microseconds taken to stabilise after changing state
+#define RS485_RETRIES 3 // Number of times to retry on error
+
+// Size of the transmit and receive buffers
+
+#define RS485_BUF_LEN 20
+
+enum rs485_state
+{
+ RS485_TALK,
+ RS485_TALK_TIMEOUT,
+ RS485_LISTEN,
+ RS485_LISTEN_TIMEOUT
+};
+
+class intercom
+{
+ public:
+
+#if RS485_MASTER == 1
+ intercom();
+#else
+ intercom(extruder* e);
+#endif
+
+// The master processing function. Call this in a fast loop, or from a fast repeated interrupt
+
+ void tick();
+
+// Send string to device to and wait for a reply.
+
+ char* sendPacketAndGetReply(char to, char* string);
+
+// Send a packet and check it was received
+
+ bool sendPacketAndCheckAcknowledgement(char to, char* string);
+
+// We are busy if we are talking, or in the middle of receiving a packet
+
+ bool busy();
+
+ private:
+
+ char inBuffer[RS485_BUF_LEN];
+ volatile byte inPointer;
+ char outBuffer[RS485_BUF_LEN];
+ volatile byte outPointer;
+ volatile bool inPacket;
+ volatile bool packetReceived;
+ volatile rs485_state state;
+ //char reply[RS485_BUF_LEN];
+ long wait_zero;
+#if !(RS485_MASTER == 1)
+ extruder* ex;
+#endif
+
+// Reset everything to the initial state
+
+void reset();
+
+// Reset the output buffer and its associated variables
+
+void resetOutput();
+
+// Reset the input buffer and its associated variables
+
+void resetInput();
+
+// The checksum for a string is the least-significant six bits of the sum
+// of the string's bytes added to the character RS485_CHECK. It can thus take
+// one of sixty-four values, all printable. This function sets the checsum byte
+// in a string, assumed to be a packet.
+
+void checksum(char* string);
+
+// Check the checksum of a string
+
+bool checkChecksum(char* string);
+
+// Build a packet to device to from an input string. See intercom.h for the
+// packet structure. ack should either be RS485_ACK or RS485_ERROR.
+
+void buildPacket(char to, char ack, char* string);
+
+// Switch to listen mode
+
+bool listen();
+
+// Switch to talk mode
+
+bool talk();
+
+// Something useful has happened; reset the timeout time
+
+void resetWait();
+
+// Have we waited too long for something to happen?
+
+bool tooLong();
+
+// Send string to device to.
+
+bool queuePacket(char to, char ack, char* string);
+
+// Wait for a packet to arrive. The packet will be in inBuffer[ ]
+
+bool waitForPacket();
+
+// This function is called when a packet has been received
+
+void processPacket();
+
+
+// *********************************************************************************
+
+// Error functions
+
+// The output buffer has overflowed
+
+void outputBufferOverflow();
+
+// The input buffer has overflowed
+
+void inputBufferOverflow();
+
+// An attempt has been made to start sending a new message before
+// the old one has been fully sent.
+
+void talkCollision();
+
+// An attempt has been made to get a new message before the old one has been
+// fully received or before the last transmit is finished.
+
+void listenCollision();
+
+// An attempt has been made to queue a new message while the system is busy.
+
+void queueCollision();
+
+// (Part of) the data structure has become corrupted
+
+void corrupt();
+
+// We have been trying to send a message, but something is taking too long
+
+void talkTimeout();
+
+// We have been trying to receive a message, but something has been taking too long
+
+void listenTimeout();
+
+// We have been waiting too long for an incomming packet
+
+void waitTimeout();
+
+// Some queuing error has occurred
+
+void queueError();
+
+// Waiting for a packet error
+
+void waitError();
+
+// Dud checksum
+
+void checksumError();
+
+// Dud acknowledgement
+
+void ackError();
+
+};
+
+extern intercom talker;
+
+#endif
+#endif
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.pde b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.pde
new file mode 100755
index 00000000..edd11932
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/intercom.pde
@@ -0,0 +1,540 @@
+/*
+ * Class to handle internal communications in the machine via RS485
+ *
+ * Adrian Bowyer 3 July 2009
+ *
+ */
+
+#include "intercom.h"
+
+#if MOTHERBOARD > 1
+
+
+#if RS485_MASTER == 1
+intercom::intercom()
+#else
+intercom::intercom(extruder* e)
+#endif
+{
+#if !(RS485_MASTER == 1)
+ ex = e;
+#endif
+ pinMode(RX_ENABLE_PIN, OUTPUT);
+ pinMode(TX_ENABLE_PIN, OUTPUT);
+ digitalWrite(RX_ENABLE_PIN, 0); // Listen is always on
+ reset();
+}
+
+// Switch to listen mode
+
+bool intercom::listen()
+{
+ if(inPacket)
+ {
+ listenCollision();
+ return false;
+ }
+ digitalWrite(TX_ENABLE_PIN, 0);
+ state = RS485_LISTEN;
+ delayMicrosecondsInterruptible(RS485_STABILISE);
+ resetWait();
+ return true;
+}
+
+// Switch to talk mode
+
+bool intercom::talk()
+{
+ if(state == RS485_TALK)
+ {
+ talkCollision();
+ return false;
+ }
+ digitalWrite(TX_ENABLE_PIN, 1);
+ state = RS485_TALK;
+ delayMicrosecondsInterruptible(RS485_STABILISE);
+ while(rs485Interface.available()) rs485Interface.read(); // Empty any junk from the input buffer
+ resetWait();
+ return true;
+}
+
+// Reset to the initial satate
+
+void intercom::reset()
+{
+ resetOutput();
+ resetInput();
+ listen();
+}
+
+// Reset the output buffer and its associated variables
+
+void intercom::resetOutput()
+{
+ outBuffer[0] = 0;
+ outPointer = 0;
+}
+
+// Reset the input buffer and its associated variables
+
+void intercom::resetInput()
+{
+ inBuffer[0] = 0;
+ inPointer = 0;
+ inPacket = false;
+ packetReceived = false;
+}
+
+// Something useful has happened; reset the timeout time
+
+void intercom::resetWait()
+{
+ wait_zero = millis();
+}
+
+// Have we waited too long for something to happen?
+
+bool intercom::tooLong()
+{
+ return (millis() - wait_zero > TIMEOUT);
+}
+
+
+// Set the checksum for a packet. This is the least-significant 6 bits of the sum
+// of the packet's bytes added to the character RS485_CHECK. It can thus take
+// one of 64 values, all printable.
+
+void intercom::checksum(char* packet)
+{
+ packet[P_SUM] = 1; // Can't use 0, as that would terminate the packet...
+ int cs = 0;
+ int i = 0;
+ while(packet[i])
+ {
+ cs += packet[i];
+ i++;
+ }
+ cs--; // Allow for the 1 at the start
+ cs &= 0x3F;
+ packet[P_SUM] = (char)(RS485_CHECK + cs);
+}
+
+// Check the checksum of a packet
+
+bool intercom::checkChecksum(char* packet)
+{
+ char cs = packet[P_SUM];
+ checksum(packet);
+ return (cs == packet[P_SUM]);
+}
+
+// Build a packet to device to from an input string. See intercom.h for the
+// packet structure. ack should either be RS485_ACK or RS485_ERROR.
+
+void intercom::buildPacket(char to, char ack, char* string)
+{
+ byte i, j;
+ j = 0;
+ while(j < RS485_START_BYTES)
+ {
+ outBuffer[j] = RS485_START;
+ j++;
+ }
+ outBuffer[j] = to;
+ j++;
+ outBuffer[j] = MY_NAME;
+ j++; // Checksum goes here
+ j++;
+ outBuffer[j] = ack;
+ j++;
+ i = 0;
+ while(string[i] && j < RS485_BUF_LEN - 4)
+ {
+ outBuffer[j] = string[i];
+ j++;
+ i++;
+ }
+ outBuffer[j] = 0;
+ checksum(&outBuffer[RS485_START_BYTES]);
+ outBuffer[j] = RS485_END;
+ j++;
+ outBuffer[j] = 0;
+}
+
+
+// The master processing function. Call this in a fast loop, or from a fast repeated interrupt
+
+void intercom::tick()
+{
+ char b = 0;
+
+ switch(state)
+ {
+ case RS485_TALK:
+
+ // Has what we last sent (if anything) been echoed?
+
+ if(rs485Interface.available())
+ {
+ b = rs485Interface.read();
+ resetWait();
+ } else
+ {
+ // Have we waited too long for an echo?
+
+ if(tooLong())
+ {
+ talkTimeout();
+ return;
+ }
+ }
+
+ // Was the echo (if any) the last character of a packet?
+
+ if(b == RS485_END)
+ {
+ // Yes - reset everything and go back to listening
+
+ reset();
+ return;
+ }
+
+ // Do we have anything to send?
+
+ b = outBuffer[outPointer];
+ if(!b)
+ return;
+
+ // Yes - send it and reset the timeout timer
+
+ rs485Interface.print(b, BYTE);
+ outPointer++;
+ if(outPointer >= RS485_BUF_LEN)
+ outputBufferOverflow();
+ resetWait();
+ break;
+
+ // If we have timed out while sending, reset everything and go
+ // back to listen mode
+
+ case RS485_TALK_TIMEOUT:
+ resetOutput();
+ resetInput();
+ listen();
+ break;
+
+ case RS485_LISTEN:
+ if(rs485Interface.available()) // Got anything?
+ {
+ b = rs485Interface.read();
+ switch(b)
+ {
+ case RS485_START: // Start character - reset the input buffer
+ inPointer = 0;
+ inPacket = true;
+ break;
+
+ case RS485_END: // End character - terminate, then process, the packet
+ if(inPacket)
+ {
+ inPacket = false;
+ inBuffer[inPointer] = 0;
+ processPacket();
+ }
+ break;
+
+ default: // Neither start or end - if we're in a packet it must be data
+ // if not, ignore it.
+ if(inPacket)
+ {
+ inBuffer[inPointer] = b;
+ inPointer++;
+ if(inPointer >= RS485_BUF_LEN)
+ inputBufferOverflow();
+ }
+ }
+
+ // We just received something, so reset the timeout time
+
+ resetWait();
+ } else
+ {
+
+ // If we're in a packet and we've been waiting too long for the next byte
+ // the packet has timed out.
+
+ if(inPacket && tooLong())
+ listenTimeout();
+ }
+ break;
+
+ case RS485_LISTEN_TIMEOUT:
+ resetInput();
+ listen();
+ break;
+
+ default:
+ corrupt();
+ break;
+ }
+}
+
+// We are busy if we are talking, or in the middle of receiving a packet
+
+bool intercom::busy()
+{
+ return (state == RS485_TALK) || inPacket;
+}
+
+
+// Send string to device to.
+
+bool intercom::queuePacket(char to, char ack, char* string)
+{
+ if(busy())
+ {
+ queueCollision();
+ return false;
+ }
+ buildPacket(to, ack, string);
+ talk();
+ return true;
+}
+
+// Wait for a packet to arrive. The packet will be in inBuffer[ ]
+
+bool intercom::waitForPacket()
+{
+ long timeNow = millis(); // Can't use tooLong() as tick() is using that
+ while(!packetReceived)
+ {
+ tick();
+ if(millis() - timeNow > TIMEOUT)
+ {
+ waitTimeout();
+ packetReceived = false;
+ return false;
+ }
+ }
+ packetReceived = false;
+ return true;
+}
+
+// Send a packet and get an acknowledgement - used when no data is to be returned.
+
+bool intercom::sendPacketAndCheckAcknowledgement(char to, char* string)
+{
+ if(!queuePacket(to, RS485_ACK, string))
+ {
+ queueError();
+ return false;
+ }
+
+ if(!waitForPacket())
+ {
+ waitError();
+ return false;
+ }
+
+ if(!checkChecksum(inBuffer))
+ {
+ checksumError();
+ return false;
+ }
+
+ if(inBuffer[P_ACK] != RS485_ACK)
+ {
+ ackError();
+ return false;
+ }
+
+ return true;
+
+/* byte retries = 0;
+ bool ok = false;
+ while((inBuffer[P_TO] != MY_NAME || inBuffer[P_ACK] != RS485_ACK) && retries < RS485_RETRIES && !ok)
+ {
+ if(queuePacket(to, RS485_ACK, string))
+ ok = waitForPacket();
+ ok = ok && checkChecksum(inBuffer);
+ if(!ok)
+ delay(2*TIMEOUT); // Wait twice timeout, and everything should have reset itself
+ retries++;
+ }
+ return ok;
+ */
+}
+
+// Send a packet and get data in reply. The string returned is just the data;
+// it has no packet housekeeping information in.
+
+char* intercom::sendPacketAndGetReply(char to, char* string)
+{
+ if(!sendPacketAndCheckAcknowledgement(to, string))
+ inBuffer[P_DATA] = 0;
+ return &inBuffer[P_DATA]; //strcpy(reply, &inBuffer[P_DATA]);
+ //return reply;
+}
+
+// This function is called when a packet has been received
+
+void intercom::processPacket()
+{
+ char* erep = 0;
+ char err;
+ if(inBuffer[P_TO] != MY_NAME)
+ {
+ resetInput();
+ return;
+ }
+#if !(RS485_MASTER == 1)
+
+ if(checkChecksum(inBuffer))
+ {
+ erep = ex->processCommand(&inBuffer[P_DATA]);
+ if(erep)
+ queuePacket(inBuffer[1], RS485_ACK, erep);
+ }
+
+ if(!erep)
+ {
+ err = 0;
+ queuePacket(inBuffer[1], RS485_ERROR, &err);
+ }
+
+ resetInput();
+
+#endif
+ packetReceived = true;
+}
+
+
+// *********************************************************************************
+
+// Error functions
+
+// The output buffer has overflowed
+
+void intercom::outputBufferOverflow()
+{
+ outPointer = 0;
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E1");
+#endif
+}
+
+
+// The input buffer has overflowed
+
+void intercom::inputBufferOverflow()
+{
+ resetInput();
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E2");
+#endif
+}
+
+// An attempt has been made to start sending a new message before
+// the old one has been fully sent.
+
+void intercom::talkCollision()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E3");
+#endif
+}
+
+// An attempt has been made to get a new message before the old one has been
+// fully received or before the last transmit is finished.
+
+void intercom::listenCollision()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E4");
+#endif
+}
+
+// An attempt has been made to queue a new message while the system is busy.
+
+void intercom::queueCollision()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E5");
+#endif
+}
+
+// (Part of) the data structure has become corrupted
+
+void intercom::corrupt()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E6");
+#endif
+}
+
+
+// We have been trying to send a message, but something is taking too long
+
+void intercom::talkTimeout()
+{
+ state = RS485_TALK_TIMEOUT;
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E7");
+#endif
+}
+
+// We have been trying to receive a message, but something has been taking too long
+
+void intercom::listenTimeout()
+{
+ state = RS485_LISTEN_TIMEOUT;
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E8");
+#endif
+}
+
+// We have been waiting too long for an incomming packet
+
+void intercom::waitTimeout()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "E9");
+#endif
+}
+
+void intercom::queueError()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "EA");
+#endif
+}
+
+
+void intercom::waitError()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "EB");
+#endif
+}
+
+
+void intercom::checksumError()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "EC ");
+ strcat(debugstring, inBuffer);
+#endif
+}
+
+
+void intercom::ackError()
+{
+#if RS485_MASTER == 1
+ strcpy(debugstring, "ED ");
+ strcat(debugstring, inBuffer);
+#endif
+}
+
+
+
+#endif
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/pins.h b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/pins.h
new file mode 100755
index 00000000..3871b52c
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/pins.h
@@ -0,0 +1,149 @@
+#ifndef PINS_H
+#define PINS_H
+
+#if MOTHERBOARD == 0
+
+#error The Arduino cannot run the 5D GCode interpreter
+
+/****************************************************************************************
+* Arduino pin assignment - left here as they might be useful
+*
+****************************************************************************************/
+
+#define X_STEP_PIN (byte)2
+#define X_DIR_PIN (byte)3
+#define X_MIN_PIN (byte)4
+#define X_MAX_PIN (byte)9
+
+#define Y_STEP_PIN (byte)10
+#define Y_DIR_PIN (byte)7
+#define Y_MIN_PIN (byte)8
+#define Y_MAX_PIN (byte)13
+
+#define Z_STEP_PIN (byte)19
+#define Z_DIR_PIN (byte)18
+#define Z_MIN_PIN (byte)17
+#define Z_MAX_PIN (byte)16
+
+
+//extruder pins
+#define EXTRUDER_0_MOTOR_SPEED_PIN (byte)11
+#define EXTRUDER_0_MOTOR_DIR_PIN (byte)12
+#define EXTRUDER_0_HEATER_PIN (byte)6
+#define EXTRUDER_0_FAN_PIN (byte)5
+#define EXTRUDER_0_TEMPERATURE_PIN (byte)0 // Analogue input
+#define EXTRUDER_0_VALVE_DIR_PIN (byte)16 //NB: Conflicts with Max Z!!!!
+#define EXTRUDER_0_VALVE_ENABLE_PIN (byte)15
+#define EXTRUDER_0_STEP_ENABLE_PIN 5 // 5 - NB conflicts with the fan; set -ve if no stepper
+
+
+/****************************************************************************************
+* Sanguino/RepRap Motherboard with direct-drive extruders
+*
+****************************************************************************************/
+#elif MOTHERBOARD == 1
+
+#define DEBUG_PIN 0
+
+#define X_STEP_PIN (byte)15
+#define X_DIR_PIN (byte)18
+#define X_MIN_PIN (byte)20
+#define X_MAX_PIN (byte)21
+#define X_ENABLE_PIN (byte)19
+
+#define Y_STEP_PIN (byte)23
+#define Y_DIR_PIN (byte)22
+#define Y_MIN_PIN (byte)25
+#define Y_MAX_PIN (byte)26
+#define Y_ENABLE_PIN (byte)19
+
+#define Z_STEP_PIN (byte)29
+#define Z_DIR_PIN (byte)30
+#define Z_MIN_PIN (byte)2
+#define Z_MAX_PIN (byte)1
+#define Z_ENABLE_PIN (byte)31
+
+
+//extruder pins
+#define EXTRUDER_0_MOTOR_SPEED_PIN (byte)12
+#define EXTRUDER_0_MOTOR_DIR_PIN (byte)16
+#define EXTRUDER_0_HEATER_PIN (byte)14
+#define EXTRUDER_0_FAN_PIN (byte)3
+#define EXTRUDER_0_TEMPERATURE_PIN (byte)4 // Analogue input
+#define EXTRUDER_0_VALVE_DIR_PIN (byte)17
+#define EXTRUDER_0_VALVE_ENABLE_PIN (byte)13 // Valve needs to be redesigned not to need this
+#define EXTRUDER_0_STEP_ENABLE_PIN (byte)3 // 3 - Conflicts with the fan; set -ve if no stepper
+
+#define EXTRUDER_1_MOTOR_SPEED_PIN (byte)4
+#define EXTRUDER_1_MOTOR_DIR_PIN (byte)0
+#define EXTRUDER_1_HEATER_PIN (byte)24
+#define EXTRUDER_1_FAN_PIN (byte)7
+#define EXTRUDER_1_TEMPERATURE_PIN (byte)3 // Analogue input
+#define EXTRUDER_1_VALVE_DIR_PIN (byte) 6
+#define EXTRUDER_1_VALVE_ENABLE_PIN (byte)5 // Valve needs to be redesigned not to need this
+#define EXTRUDER_1_STEP_ENABLE_PIN (byte)-1 // 7 - Conflicts with the fan; set -ve if no stepper
+
+
+/****************************************************************************************
+* RepRap Motherboard with RS485 extruders
+*
+****************************************************************************************/
+
+#elif MOTHERBOARD == 2
+
+//x axis pins
+#define X_STEP_PIN 15
+#define X_DIR_PIN 18
+#define X_ENABLE_PIN 19
+#define X_MIN_PIN 20
+#define X_MAX_PIN 21
+
+//y axis pins
+#define Y_STEP_PIN 23
+#define Y_DIR_PIN 22
+#define Y_ENABLE_PIN 24
+#define Y_MIN_PIN 25
+#define Y_MAX_PIN 26
+
+//z axis pins
+#define Z_STEP_PIN 27
+#define Z_DIR_PIN 28
+#define Z_ENABLE_PIN 29
+#define Z_MIN_PIN 30
+#define Z_MAX_PIN 31
+
+#define E_STEP_PIN 17
+#define E_DIR_PIN 16
+
+//our pin for debugging.
+
+#define DEBUG_PIN 0
+
+//our SD card pins
+#define SD_CARD_WRITE 2
+#define SD_CARD_DETECT 3
+#define SD_CARD_SELECT 4
+
+//our RS485 pins
+#define TX_ENABLE_PIN 12
+#define RX_ENABLE_PIN 13
+
+//pin for controlling the PSU.
+#define PS_ON_PIN 14
+
+/****************************************************************************************
+* Arduino Mega pin assignment
+*
+****************************************************************************************/
+
+#elif MOTHERBOARD == 3
+
+#error The Arduino Mega is not yet implemented for the 5D GCode interpreter
+
+#else
+
+#error Unknown MOTHERBOARD value in parameters.h
+
+#endif
+
+#endif
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/process_g_code.pde b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/process_g_code.pde
new file mode 100755
index 00000000..5eae5e7b
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/process_g_code.pde
@@ -0,0 +1,527 @@
+
+#include "configuration.h"
+#include "pins.h"
+#include "extruder.h"
+#include "vectors.h"
+#include "cartesian_dda.h"
+
+/* bit-flags for commands and parameters */
+#define GCODE_G (1<<0)
+#define GCODE_M (1<<1)
+#define GCODE_P (1<<2)
+#define GCODE_X (1<<3)
+#define GCODE_Y (1<<4)
+#define GCODE_Z (1<<5)
+#define GCODE_I (1<<6)
+#define GCODE_J (1<<7)
+#define GCODE_K (1<<8)
+#define GCODE_F (1<<9)
+#define GCODE_S (1<<10)
+#define GCODE_Q (1<<11)
+#define GCODE_R (1<<12)
+#define GCODE_E (1<<13)
+#define GCODE_T (1<<14)
+
+
+#define PARSE_INT(ch, str, len, val, seen, flag) \
+ case ch: \
+ len = scan_int(str, &val, &seen, flag); \
+ break;
+
+#define PARSE_FLOAT(ch, str, len, val, seen, flag) \
+ case ch: \
+ len = scan_float(str, &val, &seen, flag); \
+ break;
+
+/* gcode line parse results */
+struct GcodeParser
+{
+ unsigned int seen;
+ int G;
+ int M;
+ int T;
+ float P;
+ float X;
+ float Y;
+ float Z;
+ float E;
+ float I;
+ float J;
+ float F;
+ float S;
+ float R;
+ float Q;
+};
+
+
+//our command string
+char cmdbuffer[COMMAND_SIZE];
+char c = '?';
+byte serial_count = 0;
+boolean comment = false;
+FloatPoint fp;
+FloatPoint sp;
+
+// The following three inline functions are used for things like return to 0
+
+inline void specialMoveX(const float& x, const float& feed)
+{
+ sp = where_i_am;
+ sp.x = x;
+ sp.f = feed;
+ qMove(sp);
+}
+
+inline void specialMoveY(const float& y, const float& feed)
+{
+ sp = where_i_am;
+ sp.y = y;
+ sp.f = feed;
+ qMove(sp);
+}
+
+inline void specialMoveZ(const float& z, const float& feed)
+{
+ sp = where_i_am;
+ sp.z = z;
+ sp.f = feed;
+ qMove(sp);
+}
+
+//our feedrate variables.
+//float feedrate = SLOW_XY_FEEDRATE;
+
+/* keep track of the last G code - this is the command mode to use
+ * if there is no command in the current string
+ */
+int last_gcode_g = -1;
+
+boolean abs_mode = true; //0 = incremental; 1 = absolute
+
+float extruder_speed = 0;
+
+int scan_int(char *str, int *valp);
+int scan_float(char *str, float *valp);
+
+GcodeParser gc; /* string parse result */
+
+
+//init our string processing
+inline void init_process_string()
+{
+ serial_count = 0;
+ comment = false;
+}
+
+// Get a command and process it
+
+void get_and_do_command()
+{
+ //read in characters if we got them.
+ if (Serial.available())
+ {
+ c = Serial.read();
+ if(c == '\r')
+ c = '\n';
+ // Throw away control chars except \n
+ if(c >= ' ' || c == '\n')
+ {
+
+ //newlines are ends of commands.
+ if (c != '\n')
+ {
+ // Start of comment - ignore any bytes received from now on
+ if (c == ';')
+ comment = true;
+
+ // If we're not in comment mode, add it to our array.
+ if (!comment)
+ cmdbuffer[serial_count++] = c;
+ }
+
+ }
+ }
+
+ // Data runaway?
+ if(serial_count >= COMMAND_SIZE)
+ init_process_string();
+
+ //if we've got a real command, do it
+ if (serial_count && c == '\n')
+ {
+ // Terminate string
+ cmdbuffer[serial_count] = 0;
+
+ //process our command!
+ process_string(cmdbuffer, serial_count);
+
+ //clear command.
+ init_process_string();
+
+ // Say we're ready for the next one
+
+ if(debugstring[0] != 0)
+ {
+ Serial.print("ok ");
+ Serial.println(debugstring);
+ debugstring[0] = 0;
+ } else
+ Serial.println("ok");
+ }
+}
+
+
+
+int parse_string(struct GcodeParser * gc, char instruction[ ], int size)
+{
+ int ind;
+ int len; /* length of parameter argument */
+
+ gc->seen = 0;
+
+ len=0;
+ /* scan the string for commands and parameters, recording the arguments for each,
+ * and setting the seen flag for each that is seen
+ */
+ for (ind=0; ind<size; ind += (1+len))
+ {
+ len = 0;
+ switch (instruction[ind])
+ {
+ PARSE_INT('G', &instruction[ind+1], len, gc->G, gc->seen, GCODE_G);
+ PARSE_INT('M', &instruction[ind+1], len, gc->M, gc->seen, GCODE_M);
+ PARSE_INT('T', &instruction[ind+1], len, gc->T, gc->seen, GCODE_T);
+ PARSE_FLOAT('S', &instruction[ind+1], len, gc->S, gc->seen, GCODE_S);
+ PARSE_FLOAT('P', &instruction[ind+1], len, gc->P, gc->seen, GCODE_P);
+ PARSE_FLOAT('X', &instruction[ind+1], len, gc->X, gc->seen, GCODE_X);
+ PARSE_FLOAT('Y', &instruction[ind+1], len, gc->Y, gc->seen, GCODE_Y);
+ PARSE_FLOAT('Z', &instruction[ind+1], len, gc->Z, gc->seen, GCODE_Z);
+ PARSE_FLOAT('I', &instruction[ind+1], len, gc->I, gc->seen, GCODE_I);
+ PARSE_FLOAT('J', &instruction[ind+1], len, gc->J, gc->seen, GCODE_J);
+ PARSE_FLOAT('F', &instruction[ind+1], len, gc->F, gc->seen, GCODE_F);
+ PARSE_FLOAT('R', &instruction[ind+1], len, gc->R, gc->seen, GCODE_R);
+ PARSE_FLOAT('Q', &instruction[ind+1], len, gc->Q, gc->seen, GCODE_Q);
+ PARSE_FLOAT('E', &instruction[ind+1], len, gc->E, gc->seen, GCODE_E);
+ default:
+ break;
+ }
+ }
+}
+
+
+//Read the string and execute instructions
+void process_string(char instruction[], int size)
+{
+ //the character / means delete block... used for comments and stuff.
+ if (instruction[0] == '/')
+ return;
+
+ float fr;
+
+ fp.x = 0.0;
+ fp.y = 0.0;
+ fp.z = 0.0;
+ fp.e = 0.0;
+ fp.f = 0.0;
+
+ //get all our parameters!
+ parse_string(&gc, instruction, size);
+ /* if no command was seen, but parameters were, then use the last G code as
+ * the current command
+ */
+ if ((!(gc.seen & (GCODE_G | GCODE_M | GCODE_T))) &&
+ ((gc.seen != 0) &&
+ (last_gcode_g >= 0))
+ )
+ {
+ /* yes - so use the previous command with the new parameters */
+ gc.G = last_gcode_g;
+ gc.seen |= GCODE_G;
+ }
+ //did we get a gcode?
+ if (gc.seen & GCODE_G)
+ {
+ last_gcode_g = gc.G; /* remember this for future instructions */
+ fp = where_i_am;
+ if (abs_mode)
+ {
+ if (gc.seen & GCODE_X)
+ fp.x = gc.X;
+ if (gc.seen & GCODE_Y)
+ fp.y = gc.Y;
+ if (gc.seen & GCODE_Z)
+ fp.z = gc.Z;
+ if (gc.seen & GCODE_E)
+ fp.e = gc.E;
+ }
+ else
+ {
+ if (gc.seen & GCODE_X)
+ fp.x += gc.X;
+ if (gc.seen & GCODE_Y)
+ fp.y += gc.Y;
+ if (gc.seen & GCODE_Z)
+ fp.z += gc.Z;
+ if (gc.seen & GCODE_E)
+ fp.e += gc.E;
+ }
+
+ // Get feedrate if supplied - feedrates are always absolute???
+ if ( gc.seen & GCODE_F )
+ fp.f = gc.F;
+
+ // Process the buffered move commands first
+ // If we get one, return immediately
+
+ switch (gc.G)
+ {
+ //Rapid move
+ case 0:
+ fr = fp.f;
+ fp.f = FAST_XY_FEEDRATE;
+ qMove(fp);
+ fp.f = fr;
+ return;
+
+ // Controlled move
+ case 1:
+ qMove(fp);
+ return;
+
+ //go home.
+ case 28:
+ where_i_am.f = SLOW_XY_FEEDRATE;
+ specialMoveX(where_i_am.x - 5, FAST_XY_FEEDRATE);
+ specialMoveX(where_i_am.x - 250, FAST_XY_FEEDRATE);
+ where_i_am.x = 0;
+ where_i_am.f = SLOW_XY_FEEDRATE;
+ specialMoveX(where_i_am.x + 1, SLOW_XY_FEEDRATE);
+ specialMoveX(where_i_am.x - 10, SLOW_XY_FEEDRATE);
+ where_i_am.x = 0;
+
+ specialMoveY(where_i_am.y - 5, FAST_XY_FEEDRATE);
+ specialMoveY(where_i_am.y - 250, FAST_XY_FEEDRATE);
+ where_i_am.y = 0;
+ where_i_am.f = SLOW_XY_FEEDRATE;
+ specialMoveY(where_i_am.y + 1, SLOW_XY_FEEDRATE);
+ specialMoveY(where_i_am.y - 10, SLOW_XY_FEEDRATE);
+ where_i_am.y = 0;
+
+ where_i_am.f = SLOW_Z_FEEDRATE;
+ specialMoveZ(where_i_am.z - 0.5, FAST_Z_FEEDRATE);
+ specialMoveZ(where_i_am.z - 250, FAST_Z_FEEDRATE);
+ where_i_am.z = 0;
+ where_i_am.f = SLOW_Z_FEEDRATE;
+ specialMoveZ(where_i_am.z + 1, SLOW_Z_FEEDRATE);
+ specialMoveZ(where_i_am.z - 2, SLOW_Z_FEEDRATE);
+ where_i_am.z = 0;
+ where_i_am.f = SLOW_XY_FEEDRATE; // Most sensible feedrate to leave it in
+
+ return;
+
+
+ default:
+ break;
+ }
+
+ // Non-buffered G commands
+ // Wait till the buffer q is empty first
+
+ while(!qEmpty()) delay(WAITING_DELAY);
+ //delay(2*WAITING_DELAY); // For luck
+ switch (gc.G)
+ {
+
+ //Dwell
+ case 4:
+ delay((int)(gc.P + 0.5));
+ break;
+
+ //Inches for Units
+ case 20:
+ setUnits(false);
+ break;
+
+ //mm for Units
+ case 21:
+ setUnits(true);
+ break;
+
+ //Absolute Positioning
+ case 90:
+ abs_mode = true;
+ break;
+
+ //Incremental Positioning
+ case 91:
+ abs_mode = false;
+ break;
+
+ //Set position as fp
+ case 92:
+ setPosition(fp);
+ break;
+
+ default:
+ Serial.print("huh? G");
+ Serial.println(gc.G, DEC);
+ }
+ }
+
+
+
+
+ //find us an m code.
+ if (gc.seen & GCODE_M)
+ {
+ // Wait till the q is empty first
+ while(!qEmpty()) delay(WAITING_DELAY);
+ //delay(2*WAITING_DELAY);
+ switch (gc.M)
+ {
+ //TODO: this is a bug because search_string returns 0. gotta fix that.
+ case 0:
+ break;
+ /*
+ case 0:
+ //todo: stop program
+ break;
+
+ case 1:
+ //todo: optional stop
+ break;
+
+ case 2:
+ //todo: program end
+ break;
+ */
+
+// Now, with E codes, there is no longer any idea of turning the extruder on or off.
+// (But see valve on/off below.)
+
+/*
+ //turn extruder on, forward
+ case 101:
+ ex[extruder_in_use]->setDirection(1);
+ ex[extruder_in_use]->setSpeed(extruder_speed);
+ break;
+
+ //turn extruder on, reverse
+ case 102:
+ ex[extruder_in_use]->setDirection(0);
+ ex[extruder_in_use]->setSpeed(extruder_speed);
+ break;
+
+ //turn extruder off
+ case 103:
+ ex[extruder_in_use]->setSpeed(0);
+ break;
+*/
+ //custom code for temperature control
+ case 104:
+ if (gc.seen & GCODE_S)
+ {
+ ex[extruder_in_use]->setTemperature((int)gc.S);
+ }
+ break;
+
+ //custom code for temperature reading
+ case 105:
+ Serial.print("T:");
+ Serial.println(ex[extruder_in_use]->getTemperature());
+ break;
+
+ //turn fan on
+ case 106:
+ ex[extruder_in_use]->setCooler(255);
+ break;
+
+ //turn fan off
+ case 107:
+ ex[extruder_in_use]->setCooler(0);
+ break;
+/*
+// Extruder speed is now entirely controlled by E codes
+ //set max extruder speed, 0-255 PWM
+ case 108:
+ if (gc.seen & GCODE_S)
+ extruder_speed = gc.S;
+ break;
+*/
+
+// The valve (real, or virtual...) is now the way to control any extruder (such as
+// a pressurised paste extruder) that cannot move using E codes.
+
+ // Open the valve
+ case 126:
+ ex[extruder_in_use]->valveSet(true, (int)(gc.P + 0.5));
+ break;
+
+ // Close the valve
+ case 127:
+ ex[extruder_in_use]->valveSet(false, (int)(gc.P + 0.5));
+ break;
+
+
+ default:
+ Serial.print("Huh? M");
+ Serial.println(gc.M, DEC);
+ }
+
+
+
+ }
+
+// Tool (i.e. extruder) change?
+
+ if (gc.seen & GCODE_T)
+ {
+ while(!qEmpty()) delay(WAITING_DELAY);
+ //delay(2*WAITING_DELAY);
+ newExtruder(gc.T);
+ }
+}
+
+int scan_float(char *str, float *valp, unsigned int *seen, unsigned int flag)
+{
+ float res;
+ int len;
+ char *end;
+
+ res = (float)strtod(str, &end);
+
+ len = end - str;
+
+ if (len > 0)
+ {
+ *valp = res;
+ *seen |= flag;
+ }
+ else
+ *valp = 0;
+
+ return len; /* length of number */
+}
+
+int scan_int(char *str, int *valp, unsigned int *seen, unsigned int flag)
+{
+ int res;
+ int len;
+ char *end;
+
+ res = (int)strtol(str, &end, 10);
+ len = end - str;
+
+ if (len > 0)
+ {
+ *valp = res;
+ *seen |= flag;
+ }
+ else
+ *valp = 0;
+
+ return len; /* length of number */
+}
+
+
+
diff --git a/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/vectors.h b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/vectors.h
new file mode 100755
index 00000000..938cfe0c
--- /dev/null
+++ b/trunk/darwin/firmware/FiveD_GCode/FiveD_GCode_Interpreter/vectors.h
@@ -0,0 +1,130 @@
+// Structs to hold points in 5D space.
+
+
+#ifndef VECTORS_H
+#define VECTORS_H
+
+#define round(x) ((x)>=0?(long)((x)+0.5):(long)((x)-0.5))
+
+// Real-world units
+struct FloatPoint
+{
+ float x; // Coordinate axes
+ float y;
+ float z;
+ float e; // Extrude length
+ float f; // Feedrate
+};
+
+inline FloatPoint operator+(const FloatPoint& a, const FloatPoint& b)
+{
+ FloatPoint result;
+ result.x = a.x + b.x;
+ result.y = a.y + b.y;
+ result.z = a.z + b.z;
+ result.e = a.e + b.e;
+ result.f = a.f + b.f;
+ return result;
+}
+
+inline FloatPoint operator-(const FloatPoint& a, const FloatPoint& b)
+{
+ FloatPoint result;
+ result.x = a.x - b.x;
+ result.y = a.y - b.y;
+ result.z = a.z - b.z;
+ result.e = a.e - b.e;
+ result.f = a.f - b.f;
+ return result;
+}
+
+
+// NB - the next gives neither the scalar nor the vector product
+
+inline FloatPoint operator*(const FloatPoint& a, const FloatPoint& b)
+{
+ FloatPoint result;
+ result.x = a.x * b.x;
+ result.y = a.y * b.y;
+ result.z = a.z * b.z;
+ result.e = a.e * b.e;
+ result.f = a.f * b.f;
+ return result;
+}
+
+// Can't use fabs for this as it's defined somewhere in a #define
+
+inline FloatPoint fabsv(const FloatPoint& a)
+{
+ FloatPoint result;
+ result.x = fabs(a.x);
+ result.y = fabs(a.y);
+ result.z = fabs(a.z);
+ result.e = fabs(a.e);
+ result.f = fabs(a.f);
+ return result;
+}
+
+
+// Integer numbers of steps
+struct LongPoint
+{
+ long x; // Coordinates
+ long y;
+ long z;
+ long e; // Extrusion
+ long f; // Feedrate
+};
+
+inline LongPoint operator+(const LongPoint& a, const LongPoint& b)
+{
+ LongPoint result;
+ result.x = a.x + b.x;
+ result.y = a.y + b.y;
+ result.z = a.z + b.z;
+ result.e = a.e + b.e;
+ result.f = a.f + b.f;
+ return result;
+}
+
+inline LongPoint operator-(const LongPoint& a, const LongPoint& b)
+{
+ LongPoint result;
+ result.x = a.x - b.x;
+ result.y = a.y - b.y;
+ result.z = a.z - b.z;
+ result.e = a.e - b.e;
+ result.f = a.f - b.f;
+ return result;
+}
+
+
+inline LongPoint absv(const LongPoint& a)
+{
+ LongPoint result;
+ result.x = abs(a.x);
+ result.y = abs(a.y);
+ result.z = abs(a.z);
+ result.e = abs(a.e);
+ result.f = abs(a.f);
+ return result;
+}
+
+
+inline LongPoint roundv(const FloatPoint& a)
+{
+ LongPoint result;
+ result.x = round(a.x);
+ result.y = round(a.y);
+ result.z = round(a.z);
+ result.e = round(a.e);
+ result.f = round(a.f);
+ return result;
+}
+
+inline LongPoint to_steps(const FloatPoint& units, const FloatPoint& position)
+{
+ return roundv(units*position);
+}
+
+#endif