Added reporting messages
parent
dc93740186
commit
9331ddff19
|
@ -14,7 +14,7 @@ Command::Command(String commandString) {
|
|||
|
||||
charPointer = strtok(charBuf, " ");
|
||||
|
||||
if (charPointer[0] == 'G') {
|
||||
if (charPointer[0] == 'G' || charPointer[0] == 'F') {
|
||||
commandCodeEnum = getGCodeEnum(charPointer);
|
||||
} else {
|
||||
invalidCommand = true;
|
||||
|
@ -33,9 +33,29 @@ CommandCodeEnum Command::getGCodeEnum(char* code) {
|
|||
if (strcmp(code, "G1") == 0 || strcmp(code, "G01") == 0) {
|
||||
return G01;
|
||||
}
|
||||
if (strcmp(code, "G28") == 0) {
|
||||
return G28;
|
||||
//if (strcmp(code, "F3") == 0 || strcmp(code, "F03") == 0) {
|
||||
// return F03;
|
||||
//}
|
||||
if (strcmp(code, "F11") == 0) {
|
||||
return F11;
|
||||
}
|
||||
if (strcmp(code, "F12") == 0) {
|
||||
return F12;
|
||||
}
|
||||
if (strcmp(code, "F13") == 0) {
|
||||
return F13;
|
||||
}
|
||||
|
||||
if (strcmp(code, "F81") == 0) {
|
||||
return F81;
|
||||
}
|
||||
if (strcmp(code, "F82") == 0) {
|
||||
return F82;
|
||||
}
|
||||
if (strcmp(code, "F83") == 0) {
|
||||
return F83;
|
||||
}
|
||||
|
||||
return CODE_UNDEFINED;
|
||||
}
|
||||
|
||||
|
@ -49,7 +69,7 @@ double minusNotAllowed(double value) {
|
|||
void Command::getParameter(char* charPointer) {
|
||||
if (charPointer[0] == axisCodes[0]) {
|
||||
axisValue[0] = atof(charPointer + 1);
|
||||
axisValue[0] = minusNotAllowed(axisValue[0]);
|
||||
// axisValue[0] = minusNotAllowed(axisValue[0]);
|
||||
} else if (charPointer[0] == axisCodes[1]) {
|
||||
axisValue[1] = atof(charPointer + 1);
|
||||
} else if (charPointer[0] == axisCodes[2]) {
|
||||
|
|
|
@ -9,7 +9,16 @@ enum CommandCodeEnum
|
|||
CODE_UNDEFINED = -1,
|
||||
G00 = 0,
|
||||
G01,
|
||||
G28
|
||||
G28,
|
||||
F01,
|
||||
F02,
|
||||
F03,
|
||||
F11,
|
||||
F12,
|
||||
F13,
|
||||
F81,
|
||||
F82,
|
||||
F83
|
||||
};
|
||||
|
||||
#define NULL 0
|
||||
|
|
|
@ -8,7 +8,7 @@
|
|||
#ifndef CONFIG_H_
|
||||
#define CONFIG_H_
|
||||
|
||||
const int LOGGING = 0;
|
||||
const int LOGGING = 1;
|
||||
|
||||
const unsigned int MAX_STEPS_PER_SECOND = 100;
|
||||
const unsigned int MAX_ACCELERATION_STEPS_PER_SECOND = 2;
|
||||
|
@ -19,5 +19,6 @@ const bool AXIS_HOME_FORWARD_X = false;
|
|||
const bool AXIS_HOME_FORWARD_Y = false;
|
||||
const bool AXIS_HOME_FORWARD_Z = true;
|
||||
|
||||
const String SOFTWARE_VERSION = "GENESIS V.01.01";
|
||||
|
||||
#endif /* CONFIG_H_ */
|
||||
|
|
|
@ -8,10 +8,11 @@
|
|||
#include "CurrentState.h"
|
||||
|
||||
static CurrentState* instance;
|
||||
unsigned int x = 0;
|
||||
unsigned int y = 0;
|
||||
unsigned int z = 0;
|
||||
long x = 0;
|
||||
long y = 0;
|
||||
long z = 0;
|
||||
unsigned int speed = 0;
|
||||
bool endStopState[3][2];
|
||||
|
||||
CurrentState * CurrentState::getInstance() {
|
||||
if (!instance) {
|
||||
|
@ -56,16 +57,53 @@ void CurrentState::setZ(unsigned int newZ) {
|
|||
z = newZ;
|
||||
}
|
||||
|
||||
void CurrentState::print() {
|
||||
Serial.println("Current state");
|
||||
Serial.print("X:");
|
||||
void CurrentState::setEndStopState(unsigned int axis, unsigned int position, bool state) {
|
||||
endStopState[axis][position] = state;
|
||||
}
|
||||
|
||||
void CurrentState::printPosition() {
|
||||
Serial.print("R04");
|
||||
Serial.print(" X");
|
||||
Serial.print(x);
|
||||
Serial.print(", Y:");
|
||||
Serial.print(" Y");
|
||||
Serial.print(y);
|
||||
Serial.print(", Z:");
|
||||
Serial.println(z);
|
||||
Serial.print(", speed:");
|
||||
Serial.println(speed);
|
||||
Serial.print(" Z");
|
||||
Serial.print(z);
|
||||
Serial.print("\n");
|
||||
}
|
||||
|
||||
void CurrentState::printBool(bool value)
|
||||
{
|
||||
if (value)
|
||||
{
|
||||
Serial.print("1");
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.print("0");
|
||||
}
|
||||
}
|
||||
|
||||
void CurrentState::printEndStops() {
|
||||
Serial.print("R03");
|
||||
Serial.print(" XA");
|
||||
printBool(endStopState[0][0]);
|
||||
Serial.print(" XB");
|
||||
printBool(endStopState[0][1]);
|
||||
Serial.print(" YA");
|
||||
printBool(endStopState[1][0]);
|
||||
Serial.print(" YB");
|
||||
printBool(endStopState[1][1]);
|
||||
Serial.print(" ZA");
|
||||
printBool(endStopState[2][0]);
|
||||
Serial.print(" ZB");
|
||||
printBool(endStopState[2][1]);
|
||||
Serial.print("\n");
|
||||
}
|
||||
|
||||
void CurrentState::print() {
|
||||
printPosition();
|
||||
printEndStops();
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -19,7 +19,11 @@ public:
|
|||
void setX(unsigned int);
|
||||
void setY(unsigned int);
|
||||
void setZ(unsigned int);
|
||||
void setEndStopState(unsigned int, unsigned int, bool);
|
||||
void printPosition();
|
||||
void printEndStops();
|
||||
void print();
|
||||
void printBool(bool);
|
||||
private:
|
||||
CurrentState();
|
||||
CurrentState(CurrentState const&);
|
||||
|
|
|
@ -0,0 +1,37 @@
|
|||
|
||||
/*
|
||||
* F11Handler.cpp
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#include "F11Handler.h"
|
||||
|
||||
|
||||
static F11Handler* instance;
|
||||
|
||||
F11Handler * F11Handler::getInstance() {
|
||||
if (!instance) {
|
||||
instance = new F11Handler();
|
||||
};
|
||||
return instance;
|
||||
}
|
||||
;
|
||||
|
||||
F11Handler::F11Handler() {
|
||||
}
|
||||
|
||||
int F11Handler::execute(Command* command) {
|
||||
|
||||
if (LOGGING) {
|
||||
Serial.print("R99 HOME X\n");
|
||||
}
|
||||
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,0, true, false, false);
|
||||
if (LOGGING) {
|
||||
CurrentState::getInstance()->print();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* F11Handler.h
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#ifndef F11HANDLER_H_
|
||||
#define F11HANDLER_H_
|
||||
#include "GCodeHandler.h"
|
||||
#include "Config.h"
|
||||
#include "CurrentState.h"
|
||||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
|
||||
class F11Handler : public GCodeHandler {
|
||||
public:
|
||||
static F11Handler* getInstance();
|
||||
int execute(Command*);
|
||||
private:
|
||||
F11Handler();
|
||||
F11Handler(F11Handler const&);
|
||||
void operator=(F11Handler const&);
|
||||
long adjustStepAmount(long);
|
||||
long getNumberOfSteps(double, double);
|
||||
};
|
||||
|
||||
#endif /* F11HANDLER_H_ */
|
||||
|
|
@ -0,0 +1,37 @@
|
|||
|
||||
/*
|
||||
* F12Handler.cpp
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#include "F12Handler.h"
|
||||
|
||||
|
||||
static F12Handler* instance;
|
||||
|
||||
F12Handler * F12Handler::getInstance() {
|
||||
if (!instance) {
|
||||
instance = new F12Handler();
|
||||
};
|
||||
return instance;
|
||||
}
|
||||
;
|
||||
|
||||
F12Handler::F12Handler() {
|
||||
}
|
||||
|
||||
int F12Handler::execute(Command* command) {
|
||||
|
||||
if (LOGGING) {
|
||||
Serial.print("R99 HOME Y\n");
|
||||
}
|
||||
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,0, false, true, false);
|
||||
if (LOGGING) {
|
||||
CurrentState::getInstance()->print();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* F12Handler.h
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#ifndef F12HANDLER_H_
|
||||
#define F12HANDLER_H_
|
||||
#include "GCodeHandler.h"
|
||||
#include "Config.h"
|
||||
#include "CurrentState.h"
|
||||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
|
||||
class F12Handler : public GCodeHandler {
|
||||
public:
|
||||
static F12Handler* getInstance();
|
||||
int execute(Command*);
|
||||
private:
|
||||
F12Handler();
|
||||
F12Handler(F12Handler const&);
|
||||
void operator=(F12Handler const&);
|
||||
long adjustStepAmount(long);
|
||||
long getNumberOfSteps(double, double);
|
||||
};
|
||||
|
||||
#endif /* F12HANDLER_H_ */
|
||||
|
|
@ -0,0 +1,39 @@
|
|||
|
||||
/*
|
||||
* F13Handler.cpp
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#include "F13Handler.h"
|
||||
|
||||
|
||||
static F13Handler* instance;
|
||||
|
||||
F13Handler * F13Handler::getInstance() {
|
||||
if (!instance) {
|
||||
instance = new F13Handler();
|
||||
};
|
||||
return instance;
|
||||
}
|
||||
;
|
||||
|
||||
F13Handler::F13Handler() {
|
||||
}
|
||||
|
||||
int F13Handler::execute(Command* command) {
|
||||
|
||||
Serial.print("home\n");
|
||||
|
||||
if (LOGGING) {
|
||||
Serial.print("R99 HOME Z\n");
|
||||
}
|
||||
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,0, false, false, true);
|
||||
if (LOGGING) {
|
||||
CurrentState::getInstance()->print();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* F13Handler.h
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#ifndef F13HANDLER_H_
|
||||
#define F13HANDLER_H_
|
||||
#include "GCodeHandler.h"
|
||||
#include "Config.h"
|
||||
#include "CurrentState.h"
|
||||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
|
||||
class F13Handler : public GCodeHandler {
|
||||
public:
|
||||
static F13Handler* getInstance();
|
||||
int execute(Command*);
|
||||
private:
|
||||
F13Handler();
|
||||
F13Handler(F13Handler const&);
|
||||
void operator=(F13Handler const&);
|
||||
long adjustStepAmount(long);
|
||||
long getNumberOfSteps(double, double);
|
||||
};
|
||||
|
||||
#endif /* F13HANDLER_H_ */
|
||||
|
|
@ -0,0 +1,38 @@
|
|||
|
||||
|
||||
/*
|
||||
* F81Handler.cpp
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#include "F81Handler.h"
|
||||
|
||||
|
||||
static F81Handler* instance;
|
||||
|
||||
F81Handler * F81Handler::getInstance() {
|
||||
if (!instance) {
|
||||
instance = new F81Handler();
|
||||
};
|
||||
return instance;
|
||||
}
|
||||
;
|
||||
|
||||
F81Handler::F81Handler() {
|
||||
}
|
||||
|
||||
int F81Handler::execute(Command* command) {
|
||||
|
||||
Serial.print("home\n");
|
||||
|
||||
if (LOGGING) {
|
||||
Serial.print("R99 Report end stops\n");
|
||||
}
|
||||
|
||||
CurrentState::getInstance()->printEndStops();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* F81Handler.h
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#ifndef F81HANDLER_H_
|
||||
#define F81HANDLER_H_
|
||||
#include "GCodeHandler.h"
|
||||
#include "Config.h"
|
||||
#include "CurrentState.h"
|
||||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
|
||||
class F81Handler : public GCodeHandler {
|
||||
public:
|
||||
static F81Handler* getInstance();
|
||||
int execute(Command*);
|
||||
private:
|
||||
F81Handler();
|
||||
F81Handler(F81Handler const&);
|
||||
void operator=(F81Handler const&);
|
||||
long adjustStepAmount(long);
|
||||
long getNumberOfSteps(double, double);
|
||||
};
|
||||
|
||||
#endif /* F81HANDLER_H_ */
|
||||
|
|
@ -0,0 +1,40 @@
|
|||
|
||||
|
||||
/*
|
||||
* F82Handler.cpp
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#include "F82Handler.h"
|
||||
|
||||
|
||||
static F82Handler* instance;
|
||||
|
||||
F82Handler * F82Handler::getInstance() {
|
||||
if (!instance) {
|
||||
instance = new F82Handler();
|
||||
};
|
||||
return instance;
|
||||
}
|
||||
;
|
||||
|
||||
F82Handler::F82Handler() {
|
||||
}
|
||||
|
||||
int F82Handler::execute(Command* command) {
|
||||
|
||||
Serial.print("home\n");
|
||||
|
||||
if (LOGGING) {
|
||||
Serial.print("R99 Report current position\n");
|
||||
}
|
||||
|
||||
CurrentState::getInstance()->printPosition();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* F82Handler.h
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#ifndef F82HANDLER_H_
|
||||
#define F82HANDLER_H_
|
||||
#include "GCodeHandler.h"
|
||||
#include "Config.h"
|
||||
#include "CurrentState.h"
|
||||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
|
||||
class F82Handler : public GCodeHandler {
|
||||
public:
|
||||
static F82Handler* getInstance();
|
||||
int execute(Command*);
|
||||
private:
|
||||
F82Handler();
|
||||
F82Handler(F82Handler const&);
|
||||
void operator=(F82Handler const&);
|
||||
long adjustStepAmount(long);
|
||||
long getNumberOfSteps(double, double);
|
||||
};
|
||||
|
||||
#endif /* F82HANDLER_H_ */
|
||||
|
|
@ -0,0 +1,46 @@
|
|||
|
||||
|
||||
/*
|
||||
* F83Handler.cpp
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#include "F83Handler.h"
|
||||
|
||||
|
||||
static F83Handler* instance;
|
||||
|
||||
F83Handler * F83Handler::getInstance() {
|
||||
if (!instance) {
|
||||
instance = new F83Handler();
|
||||
};
|
||||
return instance;
|
||||
}
|
||||
;
|
||||
|
||||
F83Handler::F83Handler() {
|
||||
}
|
||||
|
||||
int F83Handler::execute(Command* command) {
|
||||
|
||||
Serial.print("home\n");
|
||||
|
||||
if (LOGGING) {
|
||||
Serial.print("R99 Report server version\n");
|
||||
}
|
||||
|
||||
Serial.print("R83 ");
|
||||
Serial.print(SOFTWARE_VERSION);
|
||||
Serial.print("\n");
|
||||
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,0, false, false, true);
|
||||
if (LOGGING) {
|
||||
CurrentState::getInstance()->print();
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* F83Handler.h
|
||||
*
|
||||
* Created on: 2014/07/21
|
||||
* Author: MattLech
|
||||
*/
|
||||
|
||||
#ifndef F83HANDLER_H_
|
||||
#define F83HANDLER_H_
|
||||
#include "GCodeHandler.h"
|
||||
#include "Config.h"
|
||||
#include "CurrentState.h"
|
||||
#include "pins.h"
|
||||
#include "Config.h"
|
||||
#include "StepperControl.h"
|
||||
|
||||
class F83Handler : public GCodeHandler {
|
||||
public:
|
||||
static F83Handler* getInstance();
|
||||
int execute(Command*);
|
||||
private:
|
||||
F83Handler();
|
||||
F83Handler(F83Handler const&);
|
||||
void operator=(F83Handler const&);
|
||||
long adjustStepAmount(long);
|
||||
long getNumberOfSteps(double, double);
|
||||
};
|
||||
|
||||
#endif /* F83HANDLER_H_ */
|
||||
|
|
@ -23,7 +23,8 @@ G00Handler::G00Handler() {
|
|||
|
||||
int G00Handler::execute(Command* command) {
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(command->getX(),
|
||||
command->getY(), command->getZ(), command->getS(), false);
|
||||
command->getY(), command->getZ(), command->getS(),
|
||||
false, false, false);
|
||||
if (LOGGING) {
|
||||
CurrentState::getInstance()->print();
|
||||
}
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
/*
|
||||
* G00Handler.cpp
|
||||
* G28Handler.cpp
|
||||
*
|
||||
* Created on: 15 maj 2014
|
||||
* Author: MattLech
|
||||
|
@ -25,7 +25,8 @@ int G28Handler::execute(Command* command) {
|
|||
|
||||
Serial.print("home\n");
|
||||
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,0, true);
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,0, false, false, true);
|
||||
StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,0, true, true, false);
|
||||
//StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,HOME_MOVEMENT_SPEED_S_P_S,true);
|
||||
if (LOGGING) {
|
||||
CurrentState::getInstance()->print();
|
||||
|
|
|
@ -47,6 +47,18 @@ GCodeHandler* GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum) {
|
|||
return G00Handler::getInstance();
|
||||
case G28:
|
||||
return G28Handler::getInstance();
|
||||
case F11:
|
||||
return F11Handler::getInstance();
|
||||
case F12:
|
||||
return F12Handler::getInstance();
|
||||
case F13:
|
||||
return F13Handler::getInstance();
|
||||
case F81:
|
||||
return F81Handler::getInstance();
|
||||
case F82:
|
||||
return F82Handler::getInstance();
|
||||
case F83:
|
||||
return F83Handler::getInstance();
|
||||
}
|
||||
return NULL;
|
||||
}
|
||||
|
|
|
@ -7,11 +7,20 @@
|
|||
|
||||
#ifndef GCODEPROCESSOR_H_
|
||||
#define GCODEPROCESSOR_H_
|
||||
|
||||
#include "Command.h"
|
||||
#include "Config.h"
|
||||
|
||||
#include "GCodeHandler.h"
|
||||
#include "G00Handler.h"
|
||||
#include "G28Handler.h"
|
||||
#include "Command.h"
|
||||
#include "Config.h"
|
||||
|
||||
#include "F11Handler.h"
|
||||
#include "F12Handler.h"
|
||||
#include "F13Handler.h"
|
||||
#include "F81Handler.h"
|
||||
#include "F82Handler.h"
|
||||
#include "F83Handler.h"
|
||||
|
||||
class GCodeProcessor {
|
||||
public:
|
||||
|
|
|
@ -290,7 +290,11 @@ int endStopAxisReached(int axis_nr, bool movement_forward) {
|
|||
return 0;
|
||||
}
|
||||
|
||||
int reportEndStops() {
|
||||
void reportEndStops() {
|
||||
|
||||
CurrentState::getInstance()->printEndStops();
|
||||
|
||||
/*
|
||||
bool x_min_endstop=(digitalRead(X_MIN_PIN) == INVERT_ENDSTOPS);
|
||||
bool x_max_endstop=(digitalRead(X_MAX_PIN) == INVERT_ENDSTOPS);
|
||||
bool y_min_endstop=(digitalRead(Y_MIN_PIN) == INVERT_ENDSTOPS);
|
||||
|
@ -313,6 +317,16 @@ int reportEndStops() {
|
|||
return 1;
|
||||
}
|
||||
return 0;
|
||||
*/
|
||||
}
|
||||
|
||||
void storeEndStops() {
|
||||
CurrentState::getInstance()->setEndStopState(0,0,digitalRead(X_MIN_PIN));
|
||||
CurrentState::getInstance()->setEndStopState(0,1,digitalRead(X_MAX_PIN));
|
||||
CurrentState::getInstance()->setEndStopState(1,0,digitalRead(Y_MIN_PIN));
|
||||
CurrentState::getInstance()->setEndStopState(1,1,digitalRead(Y_MAX_PIN));
|
||||
CurrentState::getInstance()->setEndStopState(2,0,digitalRead(Z_MIN_PIN));
|
||||
CurrentState::getInstance()->setEndStopState(3,1,digitalRead(Z_MAX_PIN));
|
||||
}
|
||||
|
||||
|
||||
|
@ -324,7 +338,8 @@ int reportEndStops() {
|
|||
* maxAccelerationStepsPerSecond - maximum number of acceleration in steps per second
|
||||
*/
|
||||
int StepperControl::moveAbsoluteConstant(long xDest, long yDest,
|
||||
long zDest, unsigned int maxStepsPerSecond, bool home) {
|
||||
long zDest, unsigned int maxStepsPerSecond,
|
||||
bool homeX, bool homeY, bool homeZ) {
|
||||
|
||||
long currentPoint[3] = { CurrentState::getInstance()->getX(),
|
||||
CurrentState::getInstance()->getY(),
|
||||
|
@ -339,36 +354,29 @@ int StepperControl::moveAbsoluteConstant(long xDest, long yDest,
|
|||
* movementLength[1] / maxLenth, 1.0 * movementLength[2] / maxLenth };
|
||||
bool homeMoveReverse[3] = { AXIS_HOME_FORWARD_X, AXIS_HOME_FORWARD_Y, AXIS_HOME_FORWARD_Z };
|
||||
|
||||
bool homeAxis[3] = { homeX, homeY, homeZ };
|
||||
bool home = homeX || homeY || homeZ;
|
||||
|
||||
unsigned long currentMillis = 0;
|
||||
unsigned long currentStepsPerSecond = maxStepsPerSecond;
|
||||
unsigned long currentSteps = 0;
|
||||
unsigned long lastStepMillis[3] = { 0, 0, 0 };
|
||||
|
||||
|
||||
/*
|
||||
Serial.print("move abs const");
|
||||
Serial.print(" x ");
|
||||
Serial.print(xDest);
|
||||
Serial.print(" y ");
|
||||
Serial.print(yDest);
|
||||
Serial.print(" z ");
|
||||
Serial.print(zDest);
|
||||
Serial.print(" s ");
|
||||
Serial.print(maxStepsPerSecond);
|
||||
Serial.print("\n");
|
||||
*/
|
||||
|
||||
bool movementDone = false;
|
||||
bool forwardMovement = true;
|
||||
bool moving = false;
|
||||
bool stepMade = false;
|
||||
|
||||
storeEndStops();
|
||||
reportEndStops();
|
||||
enableMotors(true);
|
||||
setDirections(currentPoint, destinationPoint);
|
||||
|
||||
while (!movementDone) {
|
||||
|
||||
storeEndStops();
|
||||
|
||||
stepMade = false;
|
||||
moving = false;
|
||||
|
||||
|
@ -379,7 +387,7 @@ int StepperControl::moveAbsoluteConstant(long xDest, long yDest,
|
|||
// When home is active, keep moving until end point reached
|
||||
forwardMovement = homeMoveReverse[i];
|
||||
}
|
||||
if (!endStopAxisReached(i, forwardMovement))
|
||||
if (!endStopAxisReached(i, forwardMovement) && (!home || (home && homeAxis[i])))
|
||||
{
|
||||
if (home && currentPoint[i] == destinationPoint[i]){
|
||||
// When home is active, keep moving until end point reached
|
||||
|
@ -438,12 +446,18 @@ int StepperControl::moveAbsoluteConstant(long xDest, long yDest,
|
|||
delayMicroseconds(500);
|
||||
}
|
||||
|
||||
reportEndStops();
|
||||
|
||||
/**/ enableMotors(false);
|
||||
|
||||
|
||||
CurrentState::getInstance()->setX(currentPoint[0]);
|
||||
CurrentState::getInstance()->setY(currentPoint[1]);
|
||||
CurrentState::getInstance()->setZ(currentPoint[2]);
|
||||
|
||||
CurrentState::getInstance()->setZ(currentPoint[2]);
|
||||
CurrentState::getInstance()->setZ(currentPoint[2]);
|
||||
|
||||
storeEndStops();
|
||||
reportEndStops();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -22,7 +22,8 @@ public:
|
|||
long zDest, unsigned int maxStepsPerSecond,
|
||||
unsigned int maxAccelerationStepsPerSecond);
|
||||
int moveAbsoluteConstant(long xDest, long yDest,
|
||||
long zDest, unsigned int maxStepsPerSecond, bool home);
|
||||
long zDest, unsigned int maxStepsPerSecond,
|
||||
bool homeX, bool homeY, bool homeZ);
|
||||
private:
|
||||
StepperControl();
|
||||
StepperControl(StepperControl const&);
|
||||
|
|
Loading…
Reference in New Issue