// ArduinoCNC
// Styroporschneidemaschine über serielle Schnittstelle gesteuert
// Version: 1.3
// Datum: 5-Jan-12
// Versionskommentar: Standardfunktion für Datenempfang eingeführt
// -----------------------------------------------------------------------------------------
// Hinweis: Arduino IDE muss auf Board "Diecimila" eingestellt sein
// -----------------------------------------------------------------------------------------
// Befehle, die über die Serielle Schnittstelle empfangen werden:
// '1' - Rechts Y-Achse nach oben
// '2' - Rechts Y-Achse nach unten
// '3' - Rechts X-Achse nach vorne
// '4' - Rechts X-Achse nach hinten
// '5' - Links Y-Achse nach oben
// '6' - Links Y-Achse nach unten
// '7' - Links X-Achse nach vorne
// '8' - Links X-Achse nach hinten
// '0' - Stoppt die Bewegung aller Achsen
// 'S' -
// "<DIR><hex>" - bewegt beide Seiten um <hex> Schritte
// <DIR> = 'U' Aufwärts
// <DIR> = 'D' Abwärts
// <DIR> = 'F' Vorwärts
// <DIR> = 'B' Rückwärts
// Beispiel: F00F3
// "<sign><StepHex><sign><XaspectHex><sign>YaspectHex>"
// - Übergibt einen Vector an den Arduino. Der Arduino weiß, ob für die rechte
// oder linke Seite, weil er den Vector vorher entsprechend angefragt hat.
// Die drei Vorzeichen geben die Richtung an.
// Die drei Werte sind unsigned Hex (4 Characters).
// StepHex - Anzahl der Schritte in X-Richtung
// XAspectHex - Alle wieviel Clocks wird ein X-SPINDLE_ENABLEschritt gemacht.
// YAspectHex - Alle wieviel Clocks wird ein Y-SPINDLE_ENABLEschritt gemacht.
// Beispiel: +024E+0041-003D
// "#----#----#----" - Keine weiteren Vectoren mehr d.h. Arduino hört auf danach zu fragen.
//
// Befehle, die gesendet werden:
// 'L' - Arduino fordert nächsten Vector für linke Seite an
// 'R' - Arduino fordert nächsten Vector für rechte Seite an
// 'A' - Rechter Endschalter in X-Richtung erreicht
// 'B' - Linker Endschalter in X-Richtung erreicht
// 'a' - Rechter Endschalter in Y-Richtung erreicht
// 'b' - Linker Endschalter in Y-Richtung erreicht
#include <AccelStepper.h>
#define ENABLE 8 // grbl=8
#define SPINDLE_ENABLE 11 // grbl=12
#define X_STEP 2 // grbl=2
#define Y_STEP 3 // grbl=3
#define Z_STEP 4 // grbl=4
#define A_STEP 12 // grbl spindle enable
#define X_DIR 5 // grbl=5
#define Y_DIR 6 // grbl=6
#define Z_DIR 7 // grbl=7
#define A_DIR 13 // grbl spindle dir
#define LIMIT_X 9 // grbl=9
#define LIMIT_Y 10 // grbl=10
#define LIMIT_Z A4 // grbl=11
#define LIMIT_A A5
AccelStepper stepperX(AccelStepper::DRIVER, X_STEP, X_DIR);
AccelStepper stepperY(AccelStepper::DRIVER, Y_STEP, Y_DIR);
AccelStepper stepperZ(AccelStepper::DRIVER, Z_STEP, Z_DIR);
AccelStepper stepperA(AccelStepper::DRIVER, A_STEP, A_DIR);
int xrDir=0, xlDir=0, yrDir=0, ylDir=0;
boolean bitXR0, bitXR1, bitYR0, bitYR1;
boolean bitXL0, bitXL1, bitYL0, bitYL1;
int inByte='0';
int heatSetting=0;
boolean cuttingInProgress = false;
int aspXL, aspXR, aspYL, aspYR; // Anzahl der Clockticks, die bis zum nächsten Schritt jeweils übersprungen werden
int countLeft=0, countRight=0; // Anzahl der X-Schritte auf der jeweiligen Seite des aktuellen Vektors
unsigned long masterClock;
unsigned long clockXL, clockXR, clockYL, clockYR; // Schrittzähler für die jeweiligen Achsen
int xrSign, xlSign, yrSign, ylSign; // Richtungen (werden von requestVector erzeugt)
boolean validVectorL, validVectorR; // Erkennung des Endes der Vector-Daten
// ============= Initialisierung ==================================
void setup() {
// Output-Pins initialisieren
// X-Links
pinMode(X_DIR, OUTPUT);
pinMode(X_STEP, OUTPUT);
// Y-Links
pinMode(Y_DIR, OUTPUT);
pinMode(Y_STEP, OUTPUT);
// X-Rechts
pinMode(Z_DIR, OUTPUT);
pinMode(Z_STEP, OUTPUT);
// Y-Rechts
pinMode(A_DIR, OUTPUT);
pinMode(A_STEP, OUTPUT);
// Heizung für den Draht (PWM Output)
pinMode(SPINDLE_ENABLE, OUTPUT);
analogWrite(SPINDLE_ENABLE,0); // Heizung aus
//Initialisiere digitale Inputs für Endschalter
pinMode(LIMIT_X, INPUT); // X-Rechts
pinMode(LIMIT_Y, INPUT); // Y-Rechts
pinMode(LIMIT_Z, INPUT); // X-Links
pinMode(LIMIT_A, INPUT); // Y-Links
// serielle Schnittstelle initalisieren
Serial.begin(9600);
}
// ====================== Hauptschleife ==========================
void loop() {
if (cuttingInProgress) { // Maschine im Schneidemodus - Vectoren werden angefordert
if (countLeft==0) validVectorL = requestVector('L');
if (countRight==0) validVectorR = requestVector('R');
if (validVectorL || validVectorR) { // Erst wenn beide Seiten keine validen Vectoren mehr haben, wird beendet
xlDir=0; xrDir=0; ylDir=0; yrDir=0;
if (masterClock>clockXL) {
xlDir=xlSign;
clockXL+=aspXL; // das ist die zentrale Stelle, die sicherstellt, dass alle <aspXL> Durchläufe
// ein Schritt ausgeführt wird. Da hier die Richtung keine Rolle spielt,
// wird einfach immer weitergezählt.
countLeft--; // Es werden nur die Schritte in X-Richtung heruntergezählt, da sich die in Y-Richtung daraus ergeben.
}
if (masterClock>clockXR) { // analog für die anderen Achsen
xrDir=xrSign;
clockXR+=aspXR;
countRight--;
}
if (masterClock>clockYL) {
ylDir=ylSign;
clockYL+=aspYL;
}
if (masterClock>clockYR) {
yrDir=yrSign;
clockYR+=aspYR;
}
oneStep(xrDir, yrDir, xlDir, ylDir);
masterClock++;
delayMicroseconds(500);
} else {
cuttingInProgress=false; // wenn keine gültiger Vector mehr vorhanden, in manuelle Arbeitsweise umschalten
xlDir=0; xrDir=0; ylDir=0; yrDir=0;
delay(1500);
analogWrite(3,0); // Heizung ausschalten
}
}
else
{ // Maschine im manuellen Modus - Tasteneingaben abfragen.
if (Serial.available() > 0) {
inByte = Serial.read(); // Byte lesen
if (inByte=='1') yrDir=-1; else
if (inByte=='2') yrDir=1; else
if (inByte=='3') xrDir=-1; else
if (inByte=='4') xrDir=1; else
if (inByte=='5') ylDir=-1; else
if (inByte=='6') ylDir=1; else
if (inByte=='7') xlDir=-1; else
if (inByte=='8') xlDir=1; else
if (inByte=='0') {yrDir=0; xrDir=0; xlDir=0; ylDir=0; analogWrite(3,0);}
if (inByte=='H') readSetHeat();
if ((inByte=='D')||(inByte=='U')||(inByte=='B')||(inByte=='F')) readMove(inByte);
if (inByte=='S') {
cuttingInProgress = true; // schalte die Maschine in den Schneidemodus
validVectorL = true;
validVectorR = true;
countLeft=0; // stellt sicher, dass beim Umschalten in den Schneidemodus alle Zähler auf Null stehen
countRight=0; // und der erste Vector angefordert wird
clockXL=0; clockXR=0; clockYL=0; clockYR=0;
masterClock=0;
}
}
oneStep(xrDir, yrDir, xlDir, ylDir);
if (digitalRead(LIMIT_X)==LOW && xrDir==1) {xrDir=0; Serial.print('A'); delay(20);}
if (digitalRead(LIMIT_Y)==LOW && yrDir==1) {yrDir=0; Serial.print('a'); delay(20);}
if (digitalRead(LIMIT_Z)==LOW && xlDir==1) {xlDir=0; Serial.print('B'); delay(20);}
if (digitalRead(LIMIT_A)==LOW && ylDir==1) {ylDir=0; Serial.print('b'); delay(20);}
delay(10);
}
}
// Wert für den eingestellten Heizstrom lesen und PWM entsprechend programmieren
// Format auf der seriellen Schnittstelle: Hxx mit xx = 2-Byte Hex-Zahl
void readSetHeat() {
int hexNum;
heatSetting = readNumSerial(2); // 2 Byte lesen
analogWrite(SPINDLE_ENABLE,heatSetting);
}
// Rechte und linke Seite um <steps> Schritte verfahren
// dir: U = Up, D = Down, B = Back, F = Forward
void readMove(char dir) {
int i, steps, hexNum, digit;
steps = readNumSerial(4);
for (i=0; i<steps; i++) {
if (dir=='U') oneStep(0,-1,0,-1);
if (dir=='D') oneStep(0,1,0,1);
if (dir=='B') oneStep(1,0,1,0);
if (dir=='F') oneStep(-1,0,-1,0);
delay(10);
}
}
boolean requestVector(char side) {
char stpSign, aspXSign, aspYSign;
int i;
int hexNum, steps=0, aspX=0, aspY=0, digit;
boolean exitVal;
String text;
Serial.print(side); // sende request
while (Serial.available() == 0) {} // lese Vorzeichen der Schritte
stpSign=Serial.read();
exitVal=true;
if (stpSign=='#') exitVal=false; // letzter Vector gelesen - beenden;
steps = readNumSerial(4);
while (Serial.available() == 0) {} // lese Vorzeichen von aspX
aspXSign=Serial.read();
aspX = readNumSerial(4);
while (Serial.available() == 0) {} // lese Vorzeichen von aspY
aspYSign=Serial.read();
aspY = readNumSerial(4);
if (side=='L') {
if (aspXSign=='+') xlSign=-1; else xlSign=1;
if (aspYSign=='+') ylSign=-1; else ylSign=1;
aspXL = aspX;
aspYL = aspY;
countLeft = steps;
}
if (side=='R') {
if (aspXSign=='+') xrSign=-1; else xrSign=1;
if (aspYSign=='+') yrSign=-1; else yrSign=1;
aspXR = aspX;
aspYR = aspY;
countRight = steps;
}
return(exitVal);
}
// Liest eine Hex-Zahl von der seriellen Schnittstelle.
// numberofBytes gibt die Anzahl der Hex-Characters an, die erwartet werden.
// Der Return-Wert der Funktion enthält die gelesene Zahl.
long readNumSerial(int numberOfBytes) {
int i, digit, hexNum, returnValue;
digit=1; returnValue=0;
for (i=0; i<numberOfBytes-1; i++) digit*=16;
for (i=0; i<numberOfBytes; i++) {
while (Serial.available() == 0) {}
hexNum = unHex(Serial.read());
returnValue += digit*hexNum;
digit=digit/16;
}
return(returnValue);
}
// Verwandelt eine Hex-Ziffer in eine Dezimalzahl
int unHex(char hexChar) {
int (outByte);
if (hexChar>='A') outByte=hexChar-'A'+10; else outByte=hexChar-'0';
return(outByte);
}
// Führt einen Schritt auf einer oder mehreren Achsen aus
// -1 rückwärts
// 1 vorwärts
// 0 kein Schritt
void oneStep(int xr, int yr, int xl, int yl) {
// boolean b0xr, b0yr, b0xl, b0yl;
//
// b0xr=bitXR0; // alten Zustand zwischenspeichern
// b0yr=bitYR0;
// b0xl=bitXL0;
// b0yl=bitYL0;
//
// if (xr==1) {bitXR0 = !bitXR1; bitXR1 = b0xr;};
// if (xr==-1) {bitXR0 = bitXR1; bitXR1 = !b0xr;};
// if (xl==1) {bitXL0 = !bitXL1; bitXL1 = b0xl;};
// if (xl==-1) {bitXL0 = bitXL1; bitXL1 = !b0xl;};
// if (yr==1) {bitYR0 = !bitYR1; bitYR1 = b0yr;};
// if (yr==-1) {bitYR0 = bitYR1; bitYR1 = !b0yr;};
// if (yl==1) {bitYL0 = !bitYL1; bitYL1 = b0yl;};
// if (yl==-1) {bitYL0 = bitYL1; bitYL1 = !b0yl;};
//
// digitalWrite(8, bitXL1);
// digitalWrite(9, bitXL0);
// digitalWrite(10, bitYL0); // Hier sind die Bits auf der Platine vertauscht
// digitalWrite(11, bitYL1);
// digitalWrite(A0, bitXR1);
// digitalWrite(A1, bitXR0);
// digitalWrite(A2, bitYR1);
// digitalWrite(A3, bitYR0);
stepper1.move(xr);
stepper2.move(yr);
stepper3.move(xl);
stepper4.move(yl);
stepper1.run();
stepper2.run();
stepper3.run();
stepper4.run();
}
//------------------------------------------------------------------------------
// 4 Axis CNC Demo v2 - supports Adafruit motor shield v2
// [email protected] 2013-08-30
//------------------------------------------------------------------------------
// Copyright at end of file.
// please see http://www.github.com/MarginallyClever/GcodeCNCDemo for more information.
//------------------------------------------------------------------------------
// CONSTANTS
//------------------------------------------------------------------------------
//#define VERBOSE (1) // add to get a lot more serial output.
#define VERSION (2) // firmware version
#define BAUD (57600) // How fast is the Arduino talking?
#define MAX_BUF (64) // What is the longest message Arduino can store?
//#define STEPS_PER_TURN (200) // depends on your stepper motor. most are 200.
#define MIN_STEP_DELAY (50)
#define MAX_FEEDRATE (1000000/MIN_STEP_DELAY)
#define MIN_FEEDRATE (0.01)
#define NUM_AXIES (4)
//------------------------------------------------------------------------------
// PINOUT
//------------------------------------------------------------------------------
#define X_STEP_PIN 15
#define X_DIR_PIN 21
#define X_MIN_PIN 18
#define X_ENABLE_PIN 14
#define X_STEPSPERMM 1
#define Y_STEP_PIN 22
#define Y_DIR_PIN 23
#define Y_MIN_PIN 19
#define Y_ENABLE_PIN 14
#define Y_STEPSPERMM 1
#define Z_STEP_PIN 3
#define Z_DIR_PIN 2
#define Z_MIN_PIN 20
#define Z_ENABLE_PIN 26
#define Z_STEPSPERMM 1
#define E_STEP_PIN 1
#define E_DIR_PIN 0
#define E_ENABLE_PIN 14
#define E_STEPSPERMM 1
#define LED_PIN 27
#define FAN_PIN 4
#define HEATER_PIN 13 // extruder
#define HEATER_BED_PIN 10 // bed (change to 12 for breakout pin on header)
#define TEMP_0_PIN A7 // Analogue pin
#define TEMP_BED_PIN A6 // Analogue pin
#define SDSS 31
#define SLAVE_CLOCK 16
//------------------------------------------------------------------------------
// INCLUDES
//------------------------------------------------------------------------------
//#include <AccelStepper.h>
//------------------------------------------------------------------------------
// STRUCTS
//------------------------------------------------------------------------------
// for line()
typedef struct {
long deltaSteps;
long absdeltaSteps;
int dir;
long overSteps;
} Axis;
//------------------------------------------------------------------------------
// GLOBALS
//------------------------------------------------------------------------------
Axis a[4]; // for line()
Axis atemp; // for line()
char buffer[MAX_BUF]; // where we store the message until we get a ';'
int sofar; // how much is in the buffer
float px, py, pz, pe; // location in mm
// speeds
float fr=0; // Feedrate human version
long step_delay; // Feedrate machine version
// settings
char mode_abs=1; // absolute mode?
//------------------------------------------------------------------------------
// METHODS
//------------------------------------------------------------------------------
/**
* delay for the appropriate number of microseconds
* @input ms how many milliseconds to wait
*/
void pause(long ms) {
delay(ms/1000);
delayMicroseconds(ms%1000); // delayMicroseconds doesn't work for values > ~16k.
}
/**
* Set the feedrate (speed motors will move)
* @input nfr the new speed in steps/second
*/
void feedrate(float nfr) {
if(fr==nfr) return; // same as last time? quit now.
if(nfr>MAX_FEEDRATE || nfr<MIN_FEEDRATE) { // don't allow crazy feed rates
Serial.print(F("New feedrate must be greater than "));
Serial.print(MIN_FEEDRATE);
Serial.print(F("steps/s and less than "));
Serial.print(MAX_FEEDRATE);
Serial.println(F("steps/s."));
return;
}
step_delay = 1000000.0/nfr;
fr=nfr;
}
/**
* Set the logical position
* @input npx new position x
* @input npy new position y
*/
void position(float npx,float npy,float npz,float npe) {
// here is a good place to add sanity tests
px=npx;
py=npy;
pz=npz;
pe=npe;
}
void onstep(int motor,int direction) {
#ifdef VERBOSE
char *letter="XYZE";
Serial.print(letter[motor]);
#endif
switch (motor) {
case 0:
digitalWrite(X_DIR_PIN, direction);
digitalWrite(X_STEP_PIN, HIGH);
break;
case 1:
digitalWrite(Y_DIR_PIN, direction);
digitalWrite(Y_STEP_PIN, HIGH);
break;
case 2:
digitalWrite(Z_DIR_PIN, direction);
digitalWrite(Z_STEP_PIN, HIGH);
break;
case 3:
digitalWrite(E_DIR_PIN, direction);
digitalWrite(E_STEP_PIN, HIGH);
break;
}
}
void offStep() {
digitalWrite(X_STEP_PIN, LOW);
digitalWrite(Y_STEP_PIN, LOW);
digitalWrite(Z_STEP_PIN, LOW);
digitalWrite(E_STEP_PIN, LOW);
}
void release() {
digitalWrite(X_ENABLE_PIN, LOW);
digitalWrite(Y_ENABLE_PIN, LOW);
digitalWrite(Z_ENABLE_PIN, LOW);
digitalWrite(E_ENABLE_PIN, LOW);
}
/**
* Uses bresenham's line algorithm to move both motors
* @input newx the destination x position
* @input newy the destination y position
**/
void line(float newx,float newy,float newz,float newe) {
a[0].deltaSteps = (newx-px) * X_STEPSPERMM;
a[1].deltaSteps = (newy-py) * Y_STEPSPERMM;
a[2].deltaSteps = (newz-pz) * Z_STEPSPERMM;
a[3].deltaSteps = (newe-pe) * E_STEPSPERMM;
long i,j,maxsteps=0;
// run over axis
for(i=0;i<NUM_AXIES;++i) {
// pos delta
a[i].absdeltaSteps = abs(a[i].deltaSteps);
// direction
a[i].dir = a[i].deltaSteps > 0 ? 1:0;
// find axis with most steps to do
if( maxsteps < a[i].absdeltaSteps )
maxsteps = a[i].absdeltaSteps;
// reset over
a[i].overSteps=0;
}
#ifdef VERBOSE
Serial.println(F("Start >"));
#endif
// for maxsteps
for( i=0; i<maxsteps; ++i ) {
// for each Axis
for(j=0;j<NUM_AXIES;++j) {
a[j].overSteps += a[j].absdeltaSteps;
if(a[j].overSteps >= maxsteps) {
a[j].overSteps -= maxsteps;
// ENABLE STEP for MOTOR HERE
onstep(j,a[j].dir);
}
}
delayMicroseconds(50);
// disable all Steps
offStep();
pause(step_delay);
}
#ifdef VERBOSE
Serial.println(F("< Done."));
#endif
position(newx,newy,newz,newe);
}
/**
* Look for character /code/ in the buffer and read the float that immediately follows it.
* @return the value found. If nothing is found, /val/ is returned.
* @input code the character to look for.
* @input val the return value if /code/ is not found.
**/
float parsenumber(char code,float val) {
char *ptr=buffer;
while(ptr && *ptr && ptr<buffer+sofar) {
if(*ptr==code) {
return atof(ptr+1);
}
ptr=strchr(ptr,' ')+1;
}
return val;
}
/**
* write a string followed by a float to the serial line. Convenient for debugging.
* @input code the string.
* @input val the float.
*/
void output(char *code,float val) {
Serial.print(code);
Serial.println(val);
}
/**
* print the current position, feedrate, and absolute mode.
*/
void where() {
output("X",px);
output("Y",py);
output("Z",pz);
output("E",pe);
output("F",fr);
Serial.println(mode_abs?"ABS":"REL");
}
/**
* display helpful information
*/
void help() {
Serial.print(F("GcodeCNCDemo4AxisV2 "));
Serial.println(VERSION);
Serial.println(F("Commands:"));
Serial.println(F("G00/G01 [X(mm)] [Y(mm)] [Z(mm)] [E(mm)] [F(feedrate)]; - linear move"));
Serial.println(F("G04 P[seconds]; - delay"));
Serial.println(F("G90; - absolute mode"));
Serial.println(F("G91; - relative mode"));
Serial.println(F("G92 [X(mm)] [Y(mm)] [Zmm] [E(mm)]; - change logical position"));
Serial.println(F("M18; - disable motors"));
Serial.println(F("M100; - this help message"));
Serial.println(F("M114; - report position and feedrate"));
}
/**
* Read the input buffer and find any recognized commands. One G or M command per line.
*/
void processCommand() {
int cmd = parsenumber('G',-1);
switch(cmd) {
case 0: // move linear
case 1: // move linear
feedrate(parsenumber('F',fr));
line( parsenumber('X',(mode_abs?px:0)) + (mode_abs?0:px),
parsenumber('Y',(mode_abs?py:0)) + (mode_abs?0:py),
parsenumber('Z',(mode_abs?pz:0)) + (mode_abs?0:pz),
parsenumber('E',(mode_abs?pe:0)) + (mode_abs?0:pe) );
break;
case 4: pause(parsenumber('P',0)*1000); break; // dwell
case 90: mode_abs=1; break; // absolute mode
case 91: mode_abs=0; break; // relative mode
case 92: // set logical position
position( parsenumber('X',0),
parsenumber('Y',0),
parsenumber('Z',0),
parsenumber('E',0) );
break;
default: break;
}
cmd = parsenumber('M',-1);
switch(cmd) {
case 18: // disable motors
release();
break;
case 100: help(); break;
case 114: where(); break;
default: break;
}
}
/**
* prepares the input buffer to receive a new message and tells the serial connected device it is ready for more.
*/
void ready() {
sofar=0; // clear input buffer
Serial.print(F(">")); // signal ready to receive input
}
/**
* First thing this machine does on startup. Runs only once.
*/
void setup() {
Serial.begin(BAUD); // open coms
pinMode(X_STEP_PIN, OUTPUT);
pinMode(X_DIR_PIN, OUTPUT);
pinMode(X_ENABLE_PIN, OUTPUT);
pinMode(X_MIN_PIN, INPUT);
pinMode(Y_STEP_PIN, OUTPUT);
pinMode(Y_DIR_PIN, OUTPUT);
pinMode(Y_ENABLE_PIN, OUTPUT);
pinMode(Y_MIN_PIN, INPUT);
pinMode(Z_STEP_PIN, OUTPUT);
pinMode(Z_DIR_PIN, OUTPUT);
pinMode(Z_ENABLE_PIN, OUTPUT);
pinMode(Z_MIN_PIN, INPUT);
pinMode(E_STEP_PIN, OUTPUT);
pinMode(E_DIR_PIN, OUTPUT);
pinMode(E_ENABLE_PIN, OUTPUT);
digitalWrite(X_ENABLE_PIN, HIGH);
digitalWrite(Y_ENABLE_PIN, HIGH);
digitalWrite(Z_ENABLE_PIN, HIGH);
digitalWrite(E_ENABLE_PIN, HIGH);
help(); // say hello
position(0,0,0,0); // set staring position
feedrate(200); // set default speed
ready();
}
/**
* After setup() this machine will repeat loop() forever.
*/
void loop() {
// listen for serial commands
while(Serial.available() > 0) { // if something is available
char c=Serial.read(); // get it
Serial.print(c); // repeat it back so I know you got the message
if(sofar<MAX_BUF) buffer[sofar++]=c; // store it
if(buffer[sofar-1]==';') break; // entire message received
}
if(sofar>0 && buffer[sofar-1]==';') {
// we got a message and it ends with a semicolon
buffer[sofar]=0; // end the buffer so string functions work right
Serial.print(F("\r\n")); // echo a return character for humans
processCommand(); // do something with the command
ready();
}
}
/**
* This file is part of GcodeCNCDemo.
*
* GcodeCNCDemo is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* GcodeCNCDemo is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with Foobar. If not, see <http://www.gnu.org/licenses/>.
*/