Version 1.4

This commit is contained in:
cocktailyogi
2015-03-29 11:38:26 +02:00
parent d8cc9bdccd
commit f4b7367399
4 changed files with 52 additions and 98 deletions

View File

@@ -24,7 +24,7 @@ Thanks to my wife and my daughter for their patience. :-)
#include <Servo.h> #include <Servo.h>
#include "SerialCommand.h" //nice lib from Stefan Rado, https://github.com/kroimon/Arduino-SerialCommand #include "SerialCommand.h" //nice lib from Stefan Rado, https://github.com/kroimon/Arduino-SerialCommand
#define initSting "EBBv13_and_above Protocol emulated by Eggduino-Firmware V1.3" #define initSting "EBBv13_and_above Protocol emulated by Eggduino-Firmware V1.4"
//Rotational Stepper //Rotational Stepper
#define step1 11 #define step1 11
#define dir1 10 #define dir1 10
@@ -37,6 +37,7 @@ Thanks to my wife and my daughter for their patience. :-)
#define penMicrostep 16 //MicrostepMode, only 1,2,4,8,16 allowed, because of Integer-Math in this Sketch #define penMicrostep 16 //MicrostepMode, only 1,2,4,8,16 allowed, because of Integer-Math in this Sketch
//Servo //Servo
#define servoPin 3 #define servoPin 3
#define PrgButton 2 //optional Pushbutton between Pin and Ground to use certain functions with Eggbot-Inkscape extension
//make Objects //make Objects
AccelStepper rotMotor(1, step1, dir1); AccelStepper rotMotor(1, step1, dir1);
@@ -48,19 +49,17 @@ Thanks to my wife and my daughter for their patience. :-)
int penMin=0; int penMin=0;
int penMax=0; int penMax=0;
int penUpPos=5; //can be overwritten from EBB-Command SC int penUpPos=5; //can be overwritten from EBB-Command SC
int penDownPos=30; //can be overwritten from EBB-Command SC int penDownPos=20; //can be overwritten from EBB-Command SC
int servoRateUp=0; //from EBB-Protocol not implemented on machine-side int servoRateUp=0; //from EBB-Protocol not implemented on machine-side
int servoRateDown=0;//from EBB-Protocol not implemented on machine-side int servoRateDown=0;//from EBB-Protocol not implemented on machine-side
uint8_t rotStepMode=16; //1/16 by default, can be changed by EBB protocol, used as correction factor
uint8_t penStepMode=16; //1/16 by default, can be changed by EBB protocol, used as correction factor
long rotStepError=0; long rotStepError=0;
long penStepError=0; long penStepError=0;
int penState=penUpPos; int penState=penUpPos;
uint32_t nodeCount=0; uint32_t nodeCount=0;
unsigned int layer=0; unsigned int layer=0;
int prgButtonState=0; boolean prgButtonState=0;
uint8_t rotStepCorrection = rotStepMode/rotMicrostep ; //devide EBB-Coordinates by this factor to get EGGduino-Steps uint8_t rotStepCorrection = 16/rotMicrostep ; //devide EBB-Coordinates by this factor to get EGGduino-Steps
uint8_t penStepCorrection = penStepMode/penMicrostep ; //devide EBB-Coordinates by this factor to get EGGduino-Steps uint8_t penStepCorrection = 16/penMicrostep ; //devide EBB-Coordinates by this factor to get EGGduino-Steps
float rotSpeed=0; float rotSpeed=0;
float penSpeed=0; // these are local variables for Function SteppermotorMove-Command, but for performance-reasons it will be initialized here float penSpeed=0; // these are local variables for Function SteppermotorMove-Command, but for performance-reasons it will be initialized here
@@ -72,4 +71,6 @@ void setup() {
void loop() { void loop() {
SCmd.readSerial(); SCmd.readSerial();
if( 0 == digitalRead(PrgButton))
prgButtonState == 1;
} }

View File

@@ -15,7 +15,7 @@ void makeComInterface(){
SCmd.addCommand("SL",setLayer); SCmd.addCommand("SL",setLayer);
SCmd.addCommand("QL",queryLayer); SCmd.addCommand("QL",queryLayer);
SCmd.addCommand("QP",queryPen); SCmd.addCommand("QP",queryPen);
SCmd.addCommand("QB",queryButton); //preparation for "PRG" Button, actually gives fake answer, SCmd.addCommand("QB",queryButton); //"PRG" Button,
SCmd.setDefaultHandler(unrecognized); // Handler for command that isn't matched (says "What?") SCmd.setDefaultHandler(unrecognized); // Handler for command that isn't matched (says "What?")
} }
@@ -31,6 +31,7 @@ void queryPen() {
void queryButton() { void queryButton() {
Serial.print(String(prgButtonState) +"\r\n"); Serial.print(String(prgButtonState) +"\r\n");
prgButtonState = 0;
sendAck(); sendAck();
} }
@@ -110,33 +111,40 @@ void stepperMove(){
//Turn on Motors, if they are off.... //Turn on Motors, if they are off....
digitalWrite(enableRotMotor, LOW) ; digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ; digitalWrite(enablePenMotor, LOW) ;
//incoming EBB-Steps will be multiplied by 16, then Integer-maths is done, result will be divided by 16 if( (1 == rotStepCorrection) && (1 == penStepCorrection) ){ // if coordinatessystems are identical
// This make thinks here really complicated, but floating point-math kills performance and memory, believe me... I tried... //set Coordinates and Speed
long rotSteps = ( (long)rotStepsEBB * 16 / rotStepCorrection) + (long)rotStepError; //correct incoming EBB-Steps to our microstep-Setting and multiply by 16 to avoid floatingpoint... rotMotor.move(rotStepsEBB);
long penSteps = ( (long)penStepsEBB * 16 / penStepCorrection) + (long)penStepError; rotMotor.setSpeed( abs( (float)rotStepsEBB * (float)1000 / (float)duration ) );
int rotStepsToGo = (int) (rotSteps/16); //Calc Steps to go, which are possible on our machine penMotor.move(penStepsEBB);
int penStepsToGo = (int) (penSteps/16); penMotor.setSpeed( abs( (float)penStepsEBB * (float)1000 / (float)duration ) );
rotStepError = (long)rotSteps - ((long) rotStepsToGo * (long)16); // calc Position-Error, if there is one }
penStepError = (long)penSteps - ((long) penStepsToGo * (long)16); else {
long temp_rotSpeed = ((long)rotStepsToGo * (long)1000 / (long)duration ); // calc Speed in Integer Math //incoming EBB-Steps will be multiplied by 16, then Integer-maths is done, result will be divided by 16
long temp_penSpeed = ((long)penStepsToGo * (long)1000 / (long)duration ) ; // This make thinks here really complicated, but floating point-math kills performance and memory, believe me... I tried...
if (temp_rotSpeed <0 ) //remove sign, there is no negative Speed.... long rotSteps = ( (long)rotStepsEBB * 16 / rotStepCorrection) + (long)rotStepError; //correct incoming EBB-Steps to our microstep-Setting and multiply by 16 to avoid floatingpoint...
temp_rotSpeed= -temp_rotSpeed; long penSteps = ( (long)penStepsEBB * 16 / penStepCorrection) + (long)penStepError;
if (temp_penSpeed <0 ) //remove sign, there is no negative Speed.... int rotStepsToGo = (int) (rotSteps/16); //Calc Steps to go, which are possible on our machine
temp_penSpeed= -temp_penSpeed; int penStepsToGo = (int) (penSteps/16);
float rotSpeed= (float) temp_rotSpeed; // type cast rotStepError = (long)rotSteps - ((long) rotStepsToGo * (long)16); // calc Position-Error, if there is one
float penSpeed= (float) temp_penSpeed; penStepError = (long)penSteps - ((long) penStepsToGo * (long)16);
rotMotor.move(rotStepsToGo); // finally, let us set the target position... long temp_rotSpeed = ((long)rotStepsToGo * (long)1000 / (long)duration ); // calc Speed in Integer Math
rotMotor.setSpeed(rotSpeed); // and the Speed! long temp_penSpeed = ((long)penStepsToGo * (long)1000 / (long)duration ) ;
penMotor.move(penStepsToGo); float rotSpeed= (float) abs(temp_rotSpeed); // type cast
penMotor.setSpeed( penSpeed ); float penSpeed= (float) abs(temp_penSpeed);
while ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) { //set Coordinates and Speed
rotMotor.move(rotStepsToGo); // finally, let us set the target position...
rotMotor.setSpeed(rotSpeed); // and the Speed!
penMotor.move(penStepsToGo);
penMotor.setSpeed( penSpeed );
}
//Start Move
while ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) {
penMotor.runSpeedToPosition(); // Moving.... moving... moving.... penMotor.runSpeedToPosition(); // Moving.... moving... moving....
rotMotor.runSpeedToPosition(); rotMotor.runSpeedToPosition();
} }
//################### Move-Code End ############################################################ //################### Move-Code End ############################################################
sendAck(); //Mission completed sendAck(); //report Mission completed
} }
} }
else else
sendError(); sendError();
@@ -229,41 +237,7 @@ void enableMotors(){
digitalWrite(enablePenMotor, HIGH) ; digitalWrite(enablePenMotor, HIGH) ;
sendAck(); sendAck();
break; break;
case 1: rotStepMode=16; case 1: digitalWrite(enableRotMotor, LOW) ;
penStepMode=16;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 2: rotStepMode=8;
penStepMode=8;
rotStepCorrection = rotStepMode/rotMicrostep;
penStepCorrection = penStepMode/penMicrostep;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 3: rotStepMode=4;
penStepMode=4;
rotStepCorrection = rotStepMode/rotMicrostep;
penStepCorrection = penStepMode/penMicrostep;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 4: rotStepMode=2;
penStepMode=2;
rotStepCorrection = rotStepMode/rotMicrostep;
penStepCorrection = penStepMode/penMicrostep;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 5: rotStepMode=1;
penStepMode=1;
rotStepCorrection = rotStepMode/rotMicrostep;
penStepCorrection = penStepMode/penMicrostep;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ; digitalWrite(enablePenMotor, LOW) ;
sendAck(); sendAck();
break; break;
@@ -278,33 +252,7 @@ void enableMotors(){
digitalWrite(enablePenMotor, HIGH) ; digitalWrite(enablePenMotor, HIGH) ;
sendAck(); sendAck();
break; break;
case 1: rotStepMode=16; case 1: digitalWrite(enableRotMotor, LOW) ;
penStepMode=16;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 2: rotStepMode=8;
penStepMode=8;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 3: rotStepMode=4;
penStepMode=4;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 4: rotStepMode=2;
penStepMode=2;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ;
sendAck();
break;
case 5: rotStepMode=1;
penStepMode=1;
digitalWrite(enableRotMotor, LOW) ;
digitalWrite(enablePenMotor, LOW) ; digitalWrite(enablePenMotor, LOW) ;
sendAck(); sendAck();
break; break;
@@ -315,7 +263,6 @@ void enableMotors(){
} }
} }
void stepperModeConfigure(){ void stepperModeConfigure(){
int cmd; int cmd;
int value; int value;

View File

@@ -3,7 +3,7 @@ Eggduino
Arduino Firmware for Eggbot / Spherebot with Inkscape-Integration Arduino Firmware for Eggbot / Spherebot with Inkscape-Integration
Version 1.3 Version 1.4s
tested with Inkscape Portable 0.91, Eggbot Extension and patched eggbot.py tested with Inkscape Portable 0.91, Eggbot Extension and patched eggbot.py
Regards: Eggduino-Firmware by Joachim Cerny, 2015 Regards: Eggduino-Firmware by Joachim Cerny, 2015
@@ -34,7 +34,7 @@ http://wiki.evilmadscientist.com/Installing_software
- Go to your Inkscape-Installationfolder and navigate to subfolder .\App\Inkscape\share\extensions - Go to your Inkscape-Installationfolder and navigate to subfolder .\App\Inkscape\share\extensions
- open File "eggbot.py" in texteditor and search for line: - open File "eggbot.py" in texteditor and search for line:
"Try any devices which seem to have EBB boards attached" "Try any devices which seem to have EBB boards attached"
- uncomment that block like this: - comment that block with "#" like this:
# Try any devices which seem to have EBB boards attached # Try any devices which seem to have EBB boards attached
# for strComPort in eggbot_scan.findEiBotBoards(): # for strComPort in eggbot_scan.findEiBotBoards():
# serialPort = self.testSerialPort( strComPort ) # serialPort = self.testSerialPort( strComPort )

View File

@@ -1,3 +1,9 @@
29.03.2015 v1.4
added prototype for PRG-Button support. somebody has to test it. Connect pushbutton between Pin2 und GND.
disabled ccordinate transform for 16-microstepping, because Inkscape sends in 16-microstepping, as well.
removed commands for changing rotStepmodes
fixed some minor bugs
26.03.2015 v1.3 26.03.2015 v1.3
updated Accelstepper-Lib updated Accelstepper-Lib
set Microstepping Factor 16 by default. set Microstepping Factor 16 by default.