Merge pull request #6 from bartebor/cocktailyogi

Some code cleanup, minor improvements and indentation fix
This commit is contained in:
cocktailyogi
2015-06-03 06:34:33 +02:00
5 changed files with 293 additions and 338 deletions

View File

@@ -1,10 +1,10 @@
/* Eggduino-Firmware by Joachim Cerny, 2014
Thanks for the nice libs ACCELSTEPPER and SERIALCOMMAND, which made this project much easier.
Thanks to the Eggbot-Team for such a funny and enjoable concept!
Thanks to my wife and my daughter for their patience. :-)
Thanks for the nice libs ACCELSTEPPER and SERIALCOMMAND, which made this project much easier.
Thanks to the Eggbot-Team for such a funny and enjoable concept!
Thanks to my wife and my daughter for their patience. :-)
*/
*/
// implemented Eggbot-Protocol-Version v13
// EBB-Command-Reference, I sourced from: http://www.schmalzhaus.com/EBB/EBBCommands.html
@@ -15,9 +15,9 @@ Thanks to my wife and my daughter for their patience. :-)
// EBB-Coordinates are coming in for 16th-Microstepmode. The Coordinate-Transforms are done in weired integer-math. Be careful, when you diecide to modify settings.
/* TODOs:
1 collision control via penMin/penMax
2 implement homing sequence via microswitch or optical device
*/
1 collision control via penMin/penMax
2 implement homing sequence via microswitch or optical device
*/
#include "AccelStepper.h" // nice lib from http://www.airspayce.com/mikem/arduino/AccelStepper/
#include <Servo.h>
@@ -27,17 +27,17 @@ Thanks to my wife and my daughter for their patience. :-)
#define initSting "EBBv13_and_above Protocol emulated by Eggduino-Firmware V1.6"
//Rotational Stepper:
#define step1 11
#define dir1 10
#define enableRotMotor 9
#define rotMicrostep 16 //MicrostepMode, only 1,2,4,8,16 allowed, because of Integer-Math in this Sketch
#define step1 11
#define dir1 10
#define enableRotMotor 9
#define rotMicrostep 16 //MicrostepMode, only 1,2,4,8,16 allowed, because of Integer-Math in this Sketch
//Pen Stepper:
#define step2 8
#define dir2 7
#define enablePenMotor 6
#define penMicrostep 16 //MicrostepMode, only 1,2,4,8,16 allowed, because of Integer-Math in this Sketch
#define step2 8
#define dir2 7
#define enablePenMotor 6
#define penMicrostep 16 //MicrostepMode, only 1,2,4,8,16 allowed, because of Integer-Math in this Sketch
#define servoPin 3 //Servo
#define servoPin 3 //Servo
// EXTRAFEATURES - UNCOMMENT TO USE THEM -------------------------------------------------------------------
@@ -45,69 +45,65 @@ Thanks to my wife and my daughter for their patience. :-)
// #define penToggleButton 12 // pen up/down button
// #define motorsButton 4 // motors enable button
// #define CommandSMQB
//-----------------------------------------------------------------------------------------------------------
#define penUpPosEEAddress ((uint16_t *)0)
#define penDownPosEEAddress ((uint16_t *)2)
#define penUpPosEEAddress ((uint16_t *)0)
#define penDownPosEEAddress ((uint16_t *)2)
//make Objects
AccelStepper rotMotor(1, step1, dir1);
AccelStepper penMotor(1, step2, dir2);
Servo penServo;
SerialCommand SCmd;
//create Buttons
#ifdef prgButton
Button prgButtonToggle(prgButton, setprgButtonState);
#endif
#ifdef penToggleButton
Button penToggle(penToggleButton, doTogglePen);
#endif
#ifdef motorsButton
Button motorsToggle(motorsButton, toggleMotors);
#endif
AccelStepper rotMotor(1, step1, dir1);
AccelStepper penMotor(1, step2, dir2);
Servo penServo;
SerialCommand SCmd;
//create Buttons
#ifdef prgButton
Button prgButtonToggle(prgButton, setprgButtonState);
#endif
#ifdef penToggleButton
Button penToggle(penToggleButton, doTogglePen);
#endif
#ifdef motorsButton
Button motorsToggle(motorsButton, toggleMotors);
#endif
// Variables... be careful, by messing around here, everything has a reason and crossrelations...
int penMin=0;
int penMax=0;
int penUpPos=5; //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 servoRateDown=0;//from EBB-Protocol not implemented on machine-side
long rotStepError=0;
long penStepError=0;
int penState=penUpPos;
uint32_t nodeCount=0;
unsigned int layer=0;
boolean prgButtonState=0;
uint8_t rotStepCorrection = 16/rotMicrostep ; //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 penSpeed=0; // these are local variables for Function SteppermotorMove-Command, but for performance-reasons it will be initialized here
boolean motorsEnabled = 0;
int penMin=0;
int penMax=0;
int penUpPos=5; //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 servoRateDown=0; //from EBB-Protocol not implemented on machine-side
long rotStepError=0;
long penStepError=0;
int penState=penUpPos;
uint32_t nodeCount=0;
unsigned int layer=0;
boolean prgButtonState=0;
uint8_t rotStepCorrection = 16/rotMicrostep ; //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 penSpeed=0; // these are local variables for Function SteppermotorMove-Command, but for performance-reasons it will be initialized here
boolean motorsEnabled = 0;
void setup() {
Serial.begin(9600);
makeComInterface();
initHardware();
Serial.begin(9600);
makeComInterface();
initHardware();
}
void loop() {
if ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) {
penMotor.runSpeedToPosition(); // Moving.... moving... moving....
rotMotor.runSpeedToPosition();
}
moveOneStep();
SCmd.readSerial();
#ifdef penToggleButton
penToggle.check();
#endif
#ifdef penToggleButton
penToggle.check();
#endif
#ifdef motorsButton
motorsToggle.check();
#endif
#ifdef motorsButton
motorsToggle.check();
#endif
#ifdef prgButton
prgButtonToggle.check();
#endif
#ifdef prgButton
prgButtonToggle.check();
#endif
}

View File

@@ -1,26 +1,23 @@
void makeComInterface(){
SCmd.addCommand("v",sendVersion);
SCmd.addCommand("EM",enableMotors);
SCmd.addCommand("SC",stepperModeConfigure);
SCmd.addCommand("SP",setPen);
SCmd.addCommand("SM",stepperMove);
#ifdef CommandSMQB
SCmd.addCommand("SMQB",stepperMoveQueryButton); // composite function enabling smooth movement
#endif
SCmd.addCommand("SE",ignore);
SCmd.addCommand("TP",togglePen);
SCmd.addCommand("PO",ignore); //Engraver command, not implemented, gives fake answer
SCmd.addCommand("NI",nodeCountIncrement);
SCmd.addCommand("ND",nodeCountDecrement);
SCmd.addCommand("SN",setNodeCount);
SCmd.addCommand("QN",queryNodeCount);
SCmd.addCommand("SL",setLayer);
SCmd.addCommand("QL",queryLayer);
SCmd.addCommand("QP",queryPen);
SCmd.addCommand("QB",queryButton); //"PRG" Button,
SCmd.setDefaultHandler(unrecognized); // Handler for command that isn't matched (says "What?")
}
SCmd.addCommand("v",sendVersion);
SCmd.addCommand("EM",enableMotors);
SCmd.addCommand("SC",stepperModeConfigure);
SCmd.addCommand("SP",setPen);
SCmd.addCommand("SM",stepperMove);
SCmd.addCommand("SE",ignore);
SCmd.addCommand("TP",togglePen);
SCmd.addCommand("PO",ignore); //Engraver command, not implemented, gives fake answer
SCmd.addCommand("NI",nodeCountIncrement);
SCmd.addCommand("ND",nodeCountDecrement);
SCmd.addCommand("SN",setNodeCount);
SCmd.addCommand("QN",queryNodeCount);
SCmd.addCommand("SL",setLayer);
SCmd.addCommand("QL",queryLayer);
SCmd.addCommand("QP",queryPen);
SCmd.addCommand("QB",queryButton); //"PRG" Button,
SCmd.setDefaultHandler(unrecognized); // Handler for command that isn't matched (says "What?")
}
void queryPen() {
char state;
@@ -39,25 +36,25 @@ void queryButton() {
}
void queryLayer() {
Serial.print(String(layer) +"\r\n");
sendAck();
Serial.print(String(layer) +"\r\n");
sendAck();
}
void setLayer() {
uint32_t value=0;
char *arg1;
arg1 = SCmd.next();
if (arg1 != NULL) {
value = atoi(arg1);
layer=value;
sendAck();
}
else
sendError();
}
uint32_t value=0;
char *arg1;
arg1 = SCmd.next();
if (arg1 != NULL) {
value = atoi(arg1);
layer=value;
sendAck();
}
else
sendError();
}
void queryNodeCount() {
Serial.print(String(nodeCount) +"\r\n");
Serial.print(String(nodeCount) +"\r\n");
sendAck();
}
@@ -86,109 +83,79 @@ void nodeCountDecrement() {
}
void stepperMove() {
uint16_t duration=0; //in ms
int penStepsEBB=0; //Pen
int rotStepsEBB=0; //Rot
while ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) {
penMotor.runSpeedToPosition(); // Moving.... moving... moving....
rotMotor.runSpeedToPosition();
}
uint16_t duration=0; //in ms
int penStepsEBB=0; //Pen
int rotStepsEBB=0; //Rot
if (!parseSMArgs(&duration, &penStepsEBB, &rotStepsEBB)) {
sendError();
return;
}
moveToDestination();
sendAck();
if ( (penStepsEBB==0) && (rotStepsEBB==0) ) {
delay(duration);
//sendAck();
return;
}
doMove(duration, penStepsEBB, rotStepsEBB);
//sendAck();
}
#ifdef CommandSMQB
void stepperMoveQueryButton() {
uint16_t duration=0; //in ms
int penStepsEBB=0; //Pen
int rotStepsEBB=0; //Rot
if (!parseSMArgs(&duration, &penStepsEBB, &rotStepsEBB)) {
if (!parseSMArgs(&duration, &penStepsEBB, &rotStepsEBB)) {
sendError();
return;
}
if ( (penStepsEBB==0) && (rotStepsEBB==0) ) {
delay(duration);
queryButton();
return;
}
// sending ACK before actual move to allow buffering
queryButton();
doMove(duration, penStepsEBB, rotStepsEBB);
}
#endif
sendAck();
if ( (penStepsEBB==0) && (rotStepsEBB==0) ) {
delay(duration);
return;
}
prepareMove(duration, penStepsEBB, rotStepsEBB);
}
void setPen(){
int cmd;
int value;
char *arg;
while ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) {
penMotor.runSpeedToPosition(); // Moving.... moving... moving....
rotMotor.runSpeedToPosition();
}
arg = SCmd.next();
if (arg != NULL) {
cmd = atoi(arg);
switch (cmd) {
case 0:
penServo.write(penUpPos);
penState=penUpPos;
break;
int cmd;
int value;
char *arg;
case 1:
penServo.write(penDownPos);
penState=penDownPos;
break;
moveToDestination();
default:
sendError();
}
}
char *val;
val = SCmd.next();
if (val != NULL) {
arg = SCmd.next();
if (arg != NULL) {
cmd = atoi(arg);
switch (cmd) {
case 0:
penServo.write(penUpPos);
penState=penUpPos;
break;
case 1:
penServo.write(penDownPos);
penState=penDownPos;
break;
default:
sendError();
}
}
char *val;
val = SCmd.next();
if (val != NULL) {
value = atoi(val);
sendAck();
delay(value);
}
if (val==NULL && arg !=NULL) {
delay(value);
}
if (val==NULL && arg !=NULL) {
sendAck();
delay(500);
}
// Serial.println("delay");
if (val==NULL && arg ==NULL)
sendError();
}
// Serial.println("delay");
if (val==NULL && arg ==NULL)
sendError();
}
void togglePen(){
int value;
char *arg;
while ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) {
penMotor.runSpeedToPosition(); // Moving.... moving... moving....
rotMotor.runSpeedToPosition();
}
arg = SCmd.next();
if (arg != NULL)
value = atoi(arg);
else
value = 500;
int value;
char *arg;
moveToDestination();
arg = SCmd.next();
if (arg != NULL)
value = atoi(arg);
else
value = 500;
doTogglePen();
sendAck();
@@ -196,102 +163,102 @@ void togglePen(){
}
void doTogglePen() {
if (penState==penUpPos) {
penServo.write(penDownPos);
penState=penDownPos;
} else {
penServo.write(penUpPos);
penState=penUpPos;
}
if (penState==penUpPos) {
penServo.write(penDownPos);
penState=penDownPos;
} else {
penServo.write(penUpPos);
penState=penUpPos;
}
}
void enableMotors(){
int cmd;
int value;
char *arg;
char *val;
arg = SCmd.next();
if (arg != NULL)
cmd = atoi(arg);
val = SCmd.next();
if (val != NULL)
value = atoi(val);
//values parsed
if ((arg != NULL) && (val == NULL)){
switch (cmd) {
case 0: motorsOff();
sendAck();
break;
case 1: motorsOn();
sendAck();
break;
default:
sendError();
}
}
//the following implementaion is a little bit cheated, because i did not know, how to implement different values for first and second argument.
if ((arg != NULL) && (val != NULL)){
switch (value) {
case 0: motorsOff();
sendAck();
break;
case 1: motorsOn();
sendAck();
break;
default:
sendError();
}
}
int cmd;
int value;
char *arg;
char *val;
arg = SCmd.next();
if (arg != NULL)
cmd = atoi(arg);
val = SCmd.next();
if (val != NULL)
value = atoi(val);
//values parsed
if ((arg != NULL) && (val == NULL)){
switch (cmd) {
case 0: motorsOff();
sendAck();
break;
case 1: motorsOn();
sendAck();
break;
default:
sendError();
}
}
//the following implementaion is a little bit cheated, because i did not know, how to implement different values for first and second argument.
if ((arg != NULL) && (val != NULL)){
switch (value) {
case 0: motorsOff();
sendAck();
break;
case 1: motorsOn();
sendAck();
break;
default:
sendError();
}
}
}
void stepperModeConfigure(){
int cmd;
int value;
char *arg;
arg = SCmd.next();
if (arg != NULL)
cmd = atoi(arg);
char *val;
val = SCmd.next();
if (val != NULL)
value = atoi(val);
if ((arg != NULL) && (val != NULL)){
switch (cmd) {
case 4: penDownPos= (int) ((float) (value-6000)/(float) 133.3); // transformation from EBB to PWM-Servo
storePenDownPosInEE();
sendAck();
break;
case 5: penUpPos= (int)((float) (value-6000)/(float) 133.3); // transformation from EBB to PWM-Servo
storePenUpPosInEE();
sendAck();
break;
case 6: //rotMin=value; ignored
sendAck();
break;
case 7: //rotMax=value; ignored
sendAck();
break;
case 11: servoRateUp=value;
sendAck();
break;
case 12: servoRateDown=value;
sendAck();
break;
default:
sendError();
}
}
int cmd;
int value;
char *arg;
arg = SCmd.next();
if (arg != NULL)
cmd = atoi(arg);
char *val;
val = SCmd.next();
if (val != NULL)
value = atoi(val);
if ((arg != NULL) && (val != NULL)){
switch (cmd) {
case 4: penDownPos= (int) ((float) (value-6000)/(float) 133.3); // transformation from EBB to PWM-Servo
storePenDownPosInEE();
sendAck();
break;
case 5: penUpPos= (int)((float) (value-6000)/(float) 133.3); // transformation from EBB to PWM-Servo
storePenUpPosInEE();
sendAck();
break;
case 6: //rotMin=value; ignored
sendAck();
break;
case 7: //rotMax=value; ignored
sendAck();
break;
case 11: servoRateUp=value;
sendAck();
break;
case 12: servoRateDown=value;
sendAck();
break;
default:
sendError();
}
}
}
void sendVersion(){
Serial.print(initSting);
Serial.print("\r\n");
}
Serial.print(initSting);
Serial.print("\r\n");
}
void unrecognized(const char *command){
sendError();
}
void unrecognized(const char *command){
sendError();
}
void ignore(){
sendAck();
}
void ignore(){
sendAck();
}

View File

@@ -1,45 +1,33 @@
void initHardware(){
// enable eeprom wait in avr/eeprom.h functions
SPMCSR &= ~SELFPRGEN;
// enable eeprom wait in avr/eeprom.h functions
SPMCSR &= ~SELFPRGEN;
loadPenPosFromEE();
loadPenPosFromEE();
pinMode(enableRotMotor, OUTPUT);
pinMode(enablePenMotor, OUTPUT);
pinMode(enableRotMotor, OUTPUT);
pinMode(enablePenMotor, OUTPUT);
#ifdef prgButton
pinMode(prgButton, INPUT_PULLUP);
#endif
#ifdef penToggleButton
pinMode(penToggleButton, INPUT_PULLUP);
#endif
#ifdef motorsButton
pinMode(motorsButton, INPUT_PULLUP);
#endif
rotMotor.setMaxSpeed(2000.0);
rotMotor.setAcceleration(10000.0);
penMotor.setMaxSpeed(2000.0);
penMotor.setAcceleration(10000.0);
motorsOff();
penServo.attach(servoPin);
penServo.write(penState);
}
rotMotor.setMaxSpeed(2000.0);
rotMotor.setAcceleration(10000.0);
penMotor.setMaxSpeed(2000.0);
penMotor.setAcceleration(10000.0);
motorsOff();
penServo.attach(servoPin);
penServo.write(penState);
}
void inline loadPenPosFromEE() {
penUpPos = eeprom_read_word(penUpPosEEAddress);
penDownPos = eeprom_read_word(penDownPosEEAddress);
penState = penUpPos;
penUpPos = eeprom_read_word(penUpPosEEAddress);
penDownPos = eeprom_read_word(penDownPosEEAddress);
penState = penUpPos;
}
void inline storePenUpPosInEE() {
eeprom_update_word(penUpPosEEAddress, penUpPos);
eeprom_update_word(penUpPosEEAddress, penUpPos);
}
void inline storePenDownPosInEE() {
eeprom_update_word(penDownPosEEAddress, penDownPos);
eeprom_update_word(penDownPosEEAddress, penDownPos);
}
void inline sendAck(){
@@ -65,7 +53,7 @@ void motorsOn() {
void toggleMotors() {
if (motorsEnabled) {
motorsOff();
} else {
} else {
motorsOn();
}
}
@@ -92,7 +80,7 @@ bool parseSMArgs(uint16_t *duration, int *penStepsEBB, int *rotStepsEBB) {
return false;
}
void doMove(uint16_t duration, int penStepsEBB, int rotStepsEBB) {
void prepareMove(uint16_t duration, int penStepsEBB, int rotStepsEBB) {
if (!motorsEnabled) {
motorsOn();
}
@@ -102,7 +90,7 @@ void doMove(uint16_t duration, int penStepsEBB, int rotStepsEBB) {
rotMotor.setSpeed( abs( (float)rotStepsEBB * (float)1000 / (float)duration ) );
penMotor.move(penStepsEBB);
penMotor.setSpeed( abs( (float)penStepsEBB * (float)1000 / (float)duration ) );
} else {
} else {
//incoming EBB-Steps will be multiplied by 16, then Integer-maths is done, result will be divided by 16
// This make thinks here really complicated, but floating point-math kills performance and memory, believe me... I tried...
long rotSteps = ( (long)rotStepsEBB * 16 / rotStepCorrection) + (long)rotStepError; //correct incoming EBB-Steps to our microstep-Setting and multiply by 16 to avoid floatingpoint...
@@ -126,12 +114,20 @@ void doMove(uint16_t duration, int penStepsEBB, int rotStepsEBB) {
penMotor.move(penStepsToGo);
penMotor.setSpeed( penSpeed );
}
/*
}
void moveOneStep() {
if ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) {
penMotor.runSpeedToPosition(); // Moving.... moving... moving....
rotMotor.runSpeedToPosition();
}
}
void moveToDestination() {
while ( penMotor.distanceToGo() || rotMotor.distanceToGo() ) {
penMotor.runSpeedToPosition(); // Moving.... moving... moving....
rotMotor.runSpeedToPosition();
}
*/
}
void setprgButtonState(){

View File

@@ -44,7 +44,3 @@ http://wiki.evilmadscientist.com/Installing_software
# return serialPort
- In my version lines 1355-1360
Todos and Feature-Wishlist:
- implement hardware-button , EGGBOT-Guys call it "PRG-Button"

View File

@@ -29,7 +29,10 @@ private:
public:
Button(byte p, ActionCb a): debounce(0), state(1), lastState(1), action(a), pin(p) {} ;
Button(byte p, ActionCb a): debounce(0), state(1), lastState(1), action(a), pin(p) {
pinMode(pin, INPUT_PULLUP);
}
void check() {
byte b = digitalRead(pin);
long t = millis();
@@ -49,10 +52,7 @@ public:
}
lastState = b;
};
}
}; //button
#endif //__BUTTON_H__