Skip to content

Commit f71e2ae

Browse files
committed
Version 0.07b Released.
1 parent df22984 commit f71e2ae

File tree

10 files changed

+1861
-39
lines changed

10 files changed

+1861
-39
lines changed

Downloads/EmcArduino_07b.zip

16.9 KB
Binary file not shown.

Instructions.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -19,7 +19,7 @@ How to going in 7 easy steps:
1919
6. Open a Terminal window and do the following:
2020

2121
copy the 9axis_arduino file to /usr/bin/ with something like:
22-
sudo cp ~/Downloads/EmcArduino_06b/9axis_arduino /usr/bin
22+
sudo cp ~/Downloads/EmcArduino_07b/9axis_arduino /usr/bin
2323

2424
then make it executable with,
2525
sudo chmod +x /usr/bin/9axis_arduino

README

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,5 +7,7 @@ components such as old steppers and computer parts to high-end linear servos.
77
Right now We're just beginning, accepting advice, contributions of code and skill
88
as well as learning too.
99

10-
Got ideas, tips, suggestions? Want to start your own branch here?
11-
Would you like to be part of our team? Just let us know.
10+
Got ideas, tips, suggestions?
11+
Would you like to be part of our team?
12+
Just let us know.
13+
http://emc2arduino.wordpress.com

pre-release/EmcArduino_07a/EmcArduino_07a.ino

Lines changed: 116 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,8 @@ Note concerning switches: Be smart!
4242
#include <digitalWriteFast.h> // http://code.google.com/p/digitalwritefast/
4343

4444
#define BAUD (115200)
45-
#define MAX_BUF (64)
45+
#define VERSION "0.07a"
46+
#define ROLE "ALL-IN-ONE"
4647

4748
#define stepsPerInchX 3200
4849
#define stepsPerInchY 3200
@@ -206,10 +207,14 @@ Note concerning switches: Be smart!
206207
#define stepPin A7 // CNC Program step switch. Optional
207208

208209
// Spindle pin config
209-
#define spindleEnablePin -1 // Optional
210-
#define spindleDirection -1 // Optional
211-
#define spindleInverted false // Set to true if spindle runs in reverse.
212-
#define spindleTach -1 // Must use an interrupt pin. Optional. *NOT YET IMPLEMENTED* COMMING SOON.
210+
#define spindleEnablePin -1 // Optional
211+
#define spindleEnableInverted false // Set to true if you need +5v to activate.
212+
#define spindleDirection -1 // Optional
213+
#define spindleDirectionInverted false // Set to true if spindle runs in reverse.
214+
215+
#define spindleTach -1 // Must be an interrupt pin. Optional.
216+
// UNO can use pin 2 or 3.
217+
// Mega2560 can use 2,3,18,19,20 or 21.
213218

214219
#define coolantMistPin -1 // Controls coolant mist pump. Optional
215220
#define coolantFloodPin -1 // Controls coolant flood pump. Optional
@@ -332,7 +337,7 @@ boolean dirState8=true;
332337
/////////////////////////////END OF USER SETTINGS///////////////////////////////
333338
////////////////////////////////////////////////////////////////////////////////
334339

335-
char buffer[MAX_BUF];
340+
char buffer[128];
336341
int sofar;
337342

338343
float pos_x;
@@ -345,8 +350,12 @@ float pos_u;
345350
float pos_v;
346351
float pos_w;
347352

353+
float revs_in=0;
354+
float spindleRPSin=0;
355+
348356
boolean stepState=LOW;
349357
unsigned long stepTimeOld=0;
358+
unsigned long spindleTimeOld=0;
350359
long stepper0Pos=0;
351360
long stepper0Goto=0;
352361
long stepper1Pos=0;
@@ -447,6 +456,30 @@ long divisor=1000000; // input divisor. Our HAL script wont send the six decimal
447456
// So here we have to put the decimal back to get the real numbers.
448457
// Used in: processCommand()
449458

459+
boolean psuState=powerSupplyInverted;
460+
boolean spindleState=spindleDirectionInverted;
461+
462+
float fbx=1;
463+
float fby=1;
464+
float fbz=1;
465+
float fba=1;
466+
float fbb=1;
467+
float fbc=1;
468+
float fbu=1;
469+
float fbv=1;
470+
float fbw=1;
471+
472+
float fbxOld=0;
473+
float fbyOld=0;
474+
float fbzOld=0;
475+
float fbaOld=0;
476+
float fbbOld=0;
477+
float fbcOld=0;
478+
float fbuOld=0;
479+
float fbvOld=0;
480+
float fbwOld=0;
481+
482+
450483
void jog(float x, float y, float z, float a, float b, float c, float u, float v, float w)
451484
{
452485
pos_x=x;
@@ -458,7 +491,6 @@ void jog(float x, float y, float z, float a, float b, float c, float u, float v,
458491
pos_u=u;
459492
pos_v=v;
460493
pos_w=w;
461-
462494
// Handle our limit switches.
463495
// Compressed to save visual space. Otherwise it would be several pages long!
464496

@@ -546,6 +578,8 @@ void processCommand()
546578
float vv=pos_v;
547579
float ww=pos_w;
548580

581+
float ss=revs_in;
582+
549583
char *ptr=buffer;
550584
while(ptr && ptr<buffer+sofar)
551585
{
@@ -564,7 +598,7 @@ void processCommand()
564598
case 'w': case 'W': ww=atof(ptr+1); ww=ww/divisor; break;
565599

566600
// Spindle speed command. In revs per second
567-
case 's': case 'S': ww=atof(ptr+1); ww=ww/divisor; break;
601+
case 's': case 'S': ss=atof(ptr+1); spindleRPSin=ss; break;
568602

569603
default: ptr=0; break;
570604
}
@@ -576,27 +610,6 @@ void processCommand()
576610
}
577611
}
578612

579-
float fbx=1;
580-
float fby=1;
581-
float fbz=1;
582-
float fba=1;
583-
float fbb=1;
584-
float fbc=1;
585-
float fbu=1;
586-
float fbv=1;
587-
float fbw=1;
588-
589-
float fbxOld=0;
590-
float fbyOld=0;
591-
float fbzOld=0;
592-
float fbaOld=0;
593-
float fbbOld=0;
594-
float fbcOld=0;
595-
float fbuOld=0;
596-
float fbvOld=0;
597-
float fbwOld=0;
598-
599-
600613
void stepLight() // Set by jog() && Used by loop()
601614
{
602615
unsigned long curTime=micros();
@@ -665,11 +678,69 @@ void stepMode(int axis, int mode) // May be omitted in the future. (Undecided)
665678
if(axis == 8 || 9){if(mode!=stepModeW){digitalWriteFast2(chanWms1,ms1);digitalWriteFast2(chanWms2,ms2);digitalWriteFast2(chanWms3,ms3);stepModeW=count;}}
666679
}
667680

668-
boolean psuState=powerSupplyInverted;
669-
boolean spindleState=spindleInverted;
681+
int determinInterrupt(int val)
682+
{
683+
if(val<0) return -1;
684+
if(val==2) return 0;
685+
if(val==3) return 1;
686+
if(val==18) return 5;
687+
if(val==19) return 4;
688+
if(val==20) return 3;
689+
if(val==21) return 2;
690+
}
691+
692+
volatile unsigned long spindleRevs=0;
693+
float spindleRPS=0;
694+
float spindleRPM=0;
695+
696+
void countSpindleRevs()
697+
{
698+
spindleRevs++;
699+
}
700+
701+
float updateSpindleRevs()
702+
{
703+
unsigned long spindleTime=millis();
704+
if(spindleTime - spindleTimeOld >= 100)
705+
{
706+
spindleRPS=spindleRevs*10.0;
707+
spindleRPM=spindleRPS*60.0;
708+
spindleRevs=0;
709+
}
710+
}
711+
712+
boolean spindleEnabled=false;
713+
boolean spindleEnableState=spindleEnableInverted;
714+
715+
boolean spindleAtSpeed()
716+
{
717+
if(spindleTach>0)
718+
{
719+
if(spindleRPSin<spindleRPS)
720+
{
721+
if(spindleRPSin*1.05<spindleRPS || !spindleEnabled)
722+
{ /* Slow down. */
723+
if(spindleEnablePin>0){digitalWriteFast2(spindleEnablePin,!spindleEnableState);}
724+
}else{
725+
if(spindleEnabled)
726+
{ /* Speed up. */
727+
if(spindleEnablePin>0){digitalWriteFast2(spindleEnablePin,spindleEnableState);}
728+
}
729+
}
730+
return true;
731+
}else{
732+
return false;
733+
}
734+
}else{
735+
return spindleEnabled; // No tach? We'll fake it.
736+
}
737+
}
670738

671739
void setup()
672740
{
741+
// If using a spindle tachometer, setup an interrupt for it.
742+
if(spindleTach>0){int result=determinInterrupt(spindleTach);attachInterrupt(result,countSpindleRevs,FALLING);}
743+
673744
// Setup Min limit switches.
674745
if(useRealMinX){pinMode(xMinPin,INPUT);if(!xMinPinInverted)digitalWriteFast2(xMinPin,HIGH);}
675746
if(useRealMinY){pinMode(yMinPin,INPUT);if(!yMinPinInverted)digitalWriteFast2(yMinPin,HIGH);}
@@ -764,7 +835,6 @@ void setup()
764835
if(coolantMistPin>0){pinMode(coolantMistPin,OUTPUT);digitalWriteFast2(coolantMistPin,LOW);}
765836
if(coolantFloodPin>0){pinMode(coolantFloodPin,OUTPUT);digitalWriteFast2(coolantFloodPin,LOW);}
766837
if(powerSupplyPin>0){pinMode(powerSupplyPin,OUTPUT);digitalWriteFast2(powerSupplyPin,psuState);}
767-
if(powerSupplyPin>0){pinMode(powerSupplyPin,OUTPUT);digitalWriteFast2(powerSupplyPin,spindleState);}
768838

769839
// Setup idle indicator led.
770840
pinMode(idleIndicator,OUTPUT);
@@ -779,6 +849,8 @@ void setup()
779849
sofar=0;
780850
}
781851

852+
boolean spindleAtSpeedStateOld;
853+
782854
void loop()
783855
{
784856
if(useEstopSwitch==true){boolean eStopState=digitalReadFast2(eStopPin);if(eStopPinInverted){eStopState=!eStopState;}if(eStopState != eStopStateOld || eStopStateOld){eStopStateOld=eStopState;Serial.print("e");Serial.println(eStopState);delay(500);}}
@@ -801,8 +873,8 @@ void loop()
801873
if(sofar>0 && buffer[sofar-3]=='+') {
802874
if(sofar>0 && buffer[sofar-2]=='P') { /* Power LED & PSU ON */ if(powerLedPin>0){digitalWriteFast2(powerLedPin,HIGH);}if(powerSupplyPin>0){digitalWriteFast2(powerSupplyPin,psuState);}}
803875
if(sofar>0 && buffer[sofar-2]=='E') { /* E-Stop Indicator ON */ if(eStopLedPin>0){digitalWriteFast2(eStopLedPin,HIGH);}}
804-
if(sofar>0 && buffer[sofar-2]=='S') { /* Spindle power ON */ if(spindleEnablePin>0){digitalWriteFast2(spindleEnablePin,HIGH);}}
805-
if(sofar>0 && buffer[sofar-2]=='D') { /* Spindle direction ON */ if(spindleDirection>0){digitalWriteFast2(spindleDirection,spindleState);}}
876+
if(sofar>0 && buffer[sofar-2]=='S') { /* Spindle power ON */ spindleEnabled=true;}
877+
if(sofar>0 && buffer[sofar-2]=='D') { /* Spindle direction CW */ if(spindleDirection>0){digitalWriteFast2(spindleDirection,spindleState);}}
806878
if(sofar>0 && buffer[sofar-2]=='M') { /* Coolant Mist ON */ if(coolantMistPin>0){digitalWriteFast2(coolantMistPin,HIGH);}}
807879
if(sofar>0 && buffer[sofar-2]=='F') { /* Coolant Flood ON */ if(coolantFloodPin>0){digitalWriteFast2(coolantFloodPin,HIGH);}}
808880
}
@@ -811,12 +883,18 @@ void loop()
811883
if(sofar>0 && buffer[sofar-3]=='-') {
812884
if(sofar>0 && buffer[sofar-2]=='P') { /* Power LED & PSU OFF */ if(powerLedPin>0){digitalWriteFast2(powerLedPin,LOW);}if(powerSupplyPin>0){digitalWriteFast2(powerSupplyPin,!psuState);}}
813885
if(sofar>0 && buffer[sofar-2]=='E') { /* E-Stop Indicator OFF */ if(eStopLedPin>0){digitalWriteFast2(eStopLedPin,LOW);}}
814-
if(sofar>0 && buffer[sofar-2]=='S') { /* Spindle power OFF */ if(spindleEnablePin>0){digitalWriteFast2(spindleEnablePin,LOW);}}
815-
if(sofar>0 && buffer[sofar-2]=='D') { /* Spindle direction OFF */ if(spindleDirection>0){digitalWriteFast2(spindleDirection,!spindleState);}}
886+
if(sofar>0 && buffer[sofar-2]=='S') { /* Spindle power OFF */ spindleEnabled=false;}
887+
if(sofar>0 && buffer[sofar-2]=='D') { /* Spindle direction CCW */ if(spindleDirection>0){digitalWriteFast2(spindleDirection,!spindleState);}}
816888
if(sofar>0 && buffer[sofar-2]=='M') { /* Coolant Mist OFF */ if(coolantMistPin>0){digitalWriteFast2(coolantMistPin,LOW);}}
817889
if(sofar>0 && buffer[sofar-2]=='F') { /* Coolant Flood OFF */ if(coolantFloodPin>0){digitalWriteFast2(coolantFloodPin,LOW);}}
818890
}
819891

892+
// Received a "?" about something give an answer.
893+
if(sofar>0 && buffer[sofar-3]=='?') {
894+
if(sofar>0 && buffer[sofar-2]=='V') { /* Report version */ Serial.println(VERSION);}
895+
if(sofar>0 && buffer[sofar-2]=='R') { /* Report role */ Serial.println(ROLE);}
896+
}
897+
820898
// if we hit a semi-colon, assume end of instruction.
821899
if(sofar>0 && buffer[sofar-1]==';') {
822900

@@ -828,5 +906,7 @@ void loop()
828906
// reset the buffer
829907
sofar=0;
830908
}
909+
updateSpindleRevs();
910+
if(!globalBusy){boolean spindleAtSpeedState=spindleAtSpeed();if(spindleAtSpeedState != spindleAtSpeedStateOld){spindleAtSpeedStateOld=spindleAtSpeedState;Serial.print("S");Serial.println(spindleAtSpeedState);}}
831911
stepLight(); // call every loop cycle to update stepper motion.
832912
}

0 commit comments

Comments
 (0)