working on parameter management

pull/4/head
TimEvWw 2014-08-06 21:04:40 -01:00
parent 641b966ee4
commit fe04f69942
15 changed files with 493 additions and 57 deletions

View File

@ -1,9 +1,15 @@
#include "Command.h"
const char axisCodes[3] = { 'X', 'Y', 'Z' };
const char speedCode = 'S';
const char axisCodes[3] = { 'X', 'Y', 'Z' };
const char speedCode = 'S';
const char parameterIdCode = 'P';
const char parameterValueCode = 'V';
double axisValue[3] = { 0.0, 0.0, 0.0 };
double speedValue = 0.0;
double speedValue = 0.0;
long parameterId = 0;
long parameterValue = 0;
CommandCodeEnum commandCodeEnum = CODE_UNDEFINED;
Command::Command(String commandString) {
@ -46,6 +52,16 @@ CommandCodeEnum Command::getGCodeEnum(char* code) {
return F13;
}
if (strcmp(code, "F20") == 0) {
return F20;
}
if (strcmp(code, "F21") == 0) {
return F21;
}
if (strcmp(code, "F22") == 0) {
return F22;
}
if (strcmp(code, "F81") == 0) {
return F81;
}
@ -69,13 +85,16 @@ double minusNotAllowed(double value) {
void Command::getParameter(char* charPointer) {
if (charPointer[0] == axisCodes[0]) {
axisValue[0] = atof(charPointer + 1);
// axisValue[0] = minusNotAllowed(axisValue[0]);
} else if (charPointer[0] == axisCodes[1]) {
axisValue[1] = atof(charPointer + 1);
} else if (charPointer[0] == axisCodes[2]) {
axisValue[2] = atof(charPointer + 1);
} else if (charPointer[0] == speedCode) {
speedValue = atof(charPointer + 1);
} else if (charPointer[0] == parameterIdCode) {
speedValue = atof(charPointer + 1);
} else if (charPointer[0] == parameterValueCode) {
speedValue = atof(charPointer + 1);
}
}
@ -108,7 +127,11 @@ double Command::getZ() {
return axisValue[2];
}
double Command::getS() {
return speedValue;
double Command::getP() {
return parameterId;
}
double Command::getV() {
return parameterValue;
}

View File

@ -16,6 +16,9 @@ enum CommandCodeEnum
F11 = 111,
F12 = 112,
F13 = 113,
F20 = 120,
F21 = 121,
F22 = 122,
F81 = 181,
F82 = 182,
F83 = 183

View File

@ -13,18 +13,48 @@ const int LOGGING = 0;
//const unsigned long STEPS_FOR_ACC_DEC = 20;
//const unsigned int MAX_ACCELERATION_STEPS_PER_SECOND = 2;
const unsigned int MOVEMENT_STEPS_ACC_DEC = 100;
const unsigned int MOVEMENT_MAX_STEPS_PER_SECOND = 1000;
const unsigned int MOVEMENT_HOME_SPEED_S_P_S = 200;
const unsigned int MOVEMENT_TIMEOUT = 30;
//const unsigned int MOVEMENT_STEPS_ACC_DEC = 100;
//const unsigned int MOVEMENT_MAX_STEPS_PER_SECOND = 1000;
//const unsigned int MOVEMENT_HOME_SPEED_S_P_S = 200;
//const unsigned int MOVEMENT_TIMEOUT = 30;
//const unsigned int INVERT_ENDSTOPS = 1;
//const bool AXIS_HOME_UP_X = false;
//const bool AXIS_HOME_UP_Y = false;
//const bool AXIS_HOME_UP_Z = true;
const unsigned int MOVEMENT_SPEED_BASE_TIME = 2000;
const unsigned int MOVEMENT_DELAY = 500;
const unsigned int INVERT_ENDSTOPS = 1;
const long PARAM_VERSION_DEFAULT = 0;
const bool AXIS_HOME_UP_X = false;
const bool AXIS_HOME_UP_Y = false;
const bool AXIS_HOME_UP_Z = true;
const long MOVEMENT_TIMEOUT_X_DEFAULT = 30;
const long MOVEMENT_TIMEOUT_Y_DEFAULT = 30;
const long MOVEMENT_TIMEOUT_Z_DEFAULT = 30;
const long MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_X_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_Y_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_Z_DEFAULT = 0;
const long MOVEMENT_STEPS_ACC_DEC_X_DEFAULT = 200;
const long MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT = 200;
const long MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT = 200;
const long MOVEMENT_HOME_UP_X_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Y_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Z_DEFAULT = 1;
const long MOVEMENT_MIN_SPD_X_DEFAULT = 0;
const long MOVEMENT_MIN_SPD_Y_DEFAULT = 0;
const long MOVEMENT_MIN_SPD_Z_DEFAULT = 0;
const long MOVEMENT_MAX_SPD_X_DEFAULT = 1000;
const long MOVEMENT_MAX_SPD_Y_DEFAULT = 1000;
const long MOVEMENT_MAX_SPD_Z_DEFAULT = 1000;
const String SOFTWARE_VERSION = "GENESIS V.01.02";

29
src/F20Handler.cpp 100644
View File

@ -0,0 +1,29 @@
/*
* F20Handler.cpp
*
* Created on: 15 maj 2014
* Author: MattLech
*/
#include "F20Handler.h"
static F20Handler* instance;
F20Handler * F20Handler::getInstance() {
if (!instance) {
instance = new F20Handler();
};
return instance;
}
;
F20Handler::F20Handler() {
}
int F20Handler::execute(Command* command) {
//ParameterList::getInstance()-readAllValues();
return 1;
}

29
src/F20Handler.h 100644
View File

@ -0,0 +1,29 @@
/*
* F20Handler.h
*
* Created on: 15 maj 2014
* Author: MattLech
*/
#ifndef F20HANDLER_H_
#define F20HANDLER_H_
#include "GCodeHandler.h"
#include "Config.h"
#include "CurrentState.h"
#include "pins.h"
#include "Config.h"
#include "StepperControl.h"
class F20Handler : public GCodeHandler {
public:
static F20Handler* getInstance();
int execute(Command*);
private:
F20Handler();
F20Handler(F20Handler const&);
void operator=(F20Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F20HANDLER_H_ */

29
src/F21Handler.cpp 100644
View File

@ -0,0 +1,29 @@
y/*
* F21Handler.cpp
*
* Created on: 15 maj 2014
* Author: MattLech
*/
#include "F21Handler.h"
static F21Handler* instance;
F21Handler * F21Handler::getInstance() {
if (!instance) {
instance = new F21Handler();
};
return instance;
}
;
F21Handler::F21Handler() {
}
int F21Handler::execute(Command* command) {
ParameterList::getInstance()-readValue(command->getP());
return 0;
}

30
src/F21Handler.h 100644
View File

@ -0,0 +1,30 @@
/*
* F21Handler.h
*
* Created on: 15 maj 2014
* Author: MattLech
*/
#ifndef F21HANDLER_H_
#define F21HANDLER_H_
#include "GCodeHandler.h"
#include "Config.h"
#include "CurrentState.h"
#include "pins.h"
#include "Config.h"
#include "StepperControl.h"
#include "ParameterList.h"
class F21Handler : public GCodeHandler {
public:
static F21Handler* getInstance();
int execute(Command*);
private:
F21Handler();
F21Handler(F21Handler const&);
void operator=(F21Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F21HANDLER_H_ */

29
src/F22Handler.cpp 100644
View File

@ -0,0 +1,29 @@
/*
* F22Handler.cpp
*
* Created on: 15 maj 2014
* Author: MattLech
*/
#include "F22Handler.h"
static F22Handler* instance;
F22Handler * F22Handler::getInstance() {
if (!instance) {
instance = new F22Handler();
};
return instance;
}
;
F22Handler::F22Handler() {
}
int F22Handler::execute(Command* command) {
ParameterList::getInstance()-readValue(command->getP() , command->getS());
return 0;
}

30
src/F22Handler.h 100644
View File

@ -0,0 +1,30 @@
/*
* F22Handler.h
*
* Created on: 15 maj 2014
* Author: MattLech
*/
#ifndef F22HANDLER_H_
#define F22HANDLER_H_
#include "GCodeHandler.h"
#include "Config.h"
#include "CurrentState.h"
#include "pins.h"
#include "Config.h"
#include "StepperControl.h"
#include "ParameterList.h"
class F22Handler : public GCodeHandler {
public:
static F22Handler* getInstance();
int execute(Command*);
private:
F22Handler();
F22Handler(F22Handler const&);
void operator=(F22Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F22HANDLER_H_ */

View File

@ -49,12 +49,22 @@ 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 F20:
return F20Handler::getInstance();
case F21:
return F21Handler::getInstance();
case F22:
return F22Handler::getInstance();
case F81:
return F81Handler::getInstance();
case F82:

View File

@ -18,6 +18,11 @@
#include "F11Handler.h"
#include "F12Handler.h"
#include "F13Handler.h"
//#include "F20Handler.h"
#include "F21Handler.h"
#include "F22Handler.h"
#include "F81Handler.h"
#include "F82Handler.h"
#include "F83Handler.h"

View File

@ -0,0 +1,93 @@
#include "Command.h"
static ParameterList* instance;
ParameterList * ParameterList::getInstance() {
if (!instance) {
instance = new ParameterList();
};
return instance;
}
ParameterList::ParameterList() {
/*
const unsigned int MOVEMENT_STEPS_ACC_DEC = 100;
const unsigned int MOVEMENT_MAX_STEPS_PER_SECOND = 1000;
const unsigned int MOVEMENT_HOME_SPEED_S_P_S = 200;
const unsigned int MOVEMENT_TIMEOUT = 30;
const unsigned int MOVEMENT_SPEED_BASE_TIME = 2000;
const unsigned int MOVEMENT_DELAY = 500;
const unsigned int INVERT_ENDSTOPS = 1;
const bool AXIS_HOME_UP_X = false;
const bool AXIS_HOME_UP_Y = false;
const bool AXIS_HOME_UP_Z = true;
*/
paramValues[PARAM_VERSION] = PARAM_VERSION_DEFAULT;
paramValues[MOVEMENT_TIMEOUT_X] = MOVEMENT_TIMEOUT_X_DEFAULT;
paramValues[MOVEMENT_TIMEOUT_Y] = MOVEMENT_TIMEOUT_Y_DEFAULT;
paramValues[MOVEMENT_TIMEOUT_Z] = MOVEMENT_TIMEOUT_Z_DEFAULT;
paramValues[MOVEMENT_INVERT_ENDPOINTS_X] = MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT;
paramValues[MOVEMENT_INVERT_ENDPOINTS_Y] = MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT;
paramValues[MOVEMENT_INVERT_ENDPOINTS_Z] = MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT;
paramValues[MOVEMENT_INVERT_MOTOR_X] = MOVEMENT_INVERT_MOTOR_X_DEFAULT;
paramValues[MOVEMENT_INVERT_MOTOR_Y] = MOVEMENT_INVERT_MOTOR_Y_DEFAULT;
paramValues[MOVEMENT_INVERT_MOTOR_Z] = MOVEMENT_INVERT_MOTOR_Z_DEFAULT;
paramValues[MOVEMENT_STEPS_ACC_DEC_X] = MOVEMENT_STEPS_ACC_DEC_X_DEFAULT;
paramValues[MOVEMENT_STEPS_ACC_DEC_Y] = MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT;
paramValues[MOVEMENT_STEPS_ACC_DEC_Z] = MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT;
paramValues[MOVEMENT_HOME_UP_X] = MOVEMENT_HOME_UP_X_DEFAULT;
paramValues[MOVEMENT_HOME_UP_Y] = MOVEMENT_HOME_UP_Y_DEFAULT;
paramValues[MOVEMENT_HOME_UP_Z] = MOVEMENT_HOME_UP_Z_DEFAULT;
paramValues[MOVEMENT_MIN_SPD_X] = MOVEMENT_MIN_SPD_X_DEFAULT;
paramValues[MOVEMENT_MIN_SPD_Y] = MOVEMENT_MIN_SPD_Y_DEFAULT;
paramValues[MOVEMENT_MIN_SPD_Z] = MOVEMENT_MIN_SPD_Z_DEFAULT;
paramValues[MOVEMENT_MAX_SPD_X] = MOVEMENT_MAX_SPD_X_DEFAULT;
paramValues[MOVEMENT_MAX_SPD_Y] = MOVEMENT_MAX_SPD_Y_DEFAULT;
paramValues[MOVEMENT_MAX_SPD_Z] = MOVEMENT_MAX_SPD_Z_DEFAULT;
}
int ParameterList::writeValue(int id, long value) {
paramValues[id] = value;
return 0;
}
int
int ParameterList::readValue(int id) {
long value = paramValues[id];
Serial.print("R22");
Serial.print(" ");
Serial.print("P");
Serial.print(id);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
return 0;
}
long ParameterList::getValue(int id {
return paramValues[id];
}

View File

@ -0,0 +1,44 @@
#ifndef PARAMETERLIST_H_
#define PARAMETERLIST_H_
#include "Arduino.h"
#include "Config.h"
//#define NULL 0
enum ParamListEnum
{
PARAM_VERSION = 0,
MOVEMENT_TIMEOUT_X,
MOVEMENT_TIMEOUT_Y,
MOVEMENT_TIMEOUT_Z,
MOVEMENT_INVERT_ENDPOINTS_X,
MOVEMENT_INVERT_ENDPOINTS_Y,
MOVEMENT_INVERT_ENDPOINTS_Z,
MOVEMENT_INVERT_MOTOR_X,
MOVEMENT_INVERT_MOTOR_Y,
MOVEMENT_INVERT_MOTOR_Z
};
/*
#define NULL 0
*/
class ParameterList {
ParamListEnum paramListEnum;
public:
static ParameterList* getInstance();
void writeValue(int id, long value);
void readValue(int id);
long getParamValue(int id);
private:
ParameterList();
virtual ~ParameterList();
long paramValues[50];
};
#endif /* PARAMETERLIST_H_ */

View File

@ -395,27 +395,58 @@ void storeEndStops() {
* maxStepsPerSecond - maximum number of steps per second
* maxAccelerationStepsPerSecond - maximum number of acceleration in steps per second
*/
int StepperControl::moveAbsoluteConstant(long xDest, long yDest,
long zDest, unsigned int maxStepsPerSecond,
bool homeX, bool homeY, bool homeZ) {
int StepperControl::moveAbsoluteConstant( long xDest, long yDest, long zDest,
unsigned int xMaxSpd, unsigned int yMaxSpd, unsigned int zMaxSpd,
bool xHome, bool yHome, bool zHome) {
long sourcePoint[3] = { CurrentState::getInstance()->getX(),
CurrentState::getInstance()->getY(),
CurrentState::getInstance()->getZ() };
long sourcePoint[3] = { CurrentState::getInstance()->getX(),
CurrentState::getInstance()->getY(),
CurrentState::getInstance()->getZ() };
long currentPoint[3] = { CurrentState::getInstance()->getX(),
CurrentState::getInstance()->getY(),
CurrentState::getInstance()->getZ() };
long currentPoint[3] = { CurrentState::getInstance()->getX(),
CurrentState::getInstance()->getY(),
CurrentState::getInstance()->getZ() };
long destinationPoint[3] = { xDest, yDest, zDest };
unsigned long movementLength[3] = { getLength(destinationPoint[0], currentPoint[0]),
getLength(destinationPoint[1], currentPoint[1]),
getLength(destinationPoint[2], currentPoint[2])};
unsigned long movementLength[3] = { getLength(destinationPoint[0], currentPoint[0]),
getLength(destinationPoint[1], currentPoint[1]),
getLength(destinationPoint[2], currentPoint[2])};
unsigned long maxLenth = getMaxLength(movementLength);
double lengthRatio[3] = { 1.0 * movementLength[0] / maxLenth, 1.0
* movementLength[1] / maxLenth, 1.0 * movementLength[2] / maxLenth };
bool homeIsUp[3] = { AXIS_HOME_UP_X, AXIS_HOME_UP_Y, AXIS_HOME_UP_Z };
double lengthRatio[3] = { 1.0 * movementLength[0] / maxLenth,
1.0 * movementLength[1] / maxLenth,
1.0 * movementLength[2] / maxLenth };
//bool homeIsUp[3] = { AXIS_HOME_UP_X, AXIS_HOME_UP_Y, AXIS_HOME_UP_Z };
bool homeIsUp[3] = { ParameterList::getInstance()-getValue(MOVEMENT_HOME_UP_X),
ParameterList::getInstance()-getValue(MOVEMENT_HOME_UP_Y),
ParameterList::getInstance()-getValue(MOVEMENT_HOME_UP_Z) };
bool speedMax[3] = { ParameterList::getInstance()-getValue(MOVEMENT_MAX_SPD_X),
ParameterList::getInstance()-getValue(MOVEMENT_MAX_SPD_Y),
ParameterList::getInstance()-getValue(MOVEMENT_MAX_SPD_Z) };
bool speedMin[3] = { ParameterList::getInstance()-getValue(MOVEMENT_MIN_SPD_X),
ParameterList::getInstance()-getValue(MOVEMENT_MIN_SPD_Y),
ParameterList::getInstance()-getValue(MOVEMENT_MIN_SPD_Z) };
bool stepsAcc[3] = { ParameterList::getInstance()-getValue(MOVEMENT_STEPS_ACC_DEC_X),
ParameterList::getInstance()-getValue(MOVEMENT_STEPS_ACC_DEC_Y),
ParameterList::getInstance()-getValue(MOVEMENT_STEPS_ACC_DEC_Z) };
bool motorInv[3] = { ParameterList::getInstance()-getValue(MOVEMENT_INVERT_MOTOR_X),
ParameterList::getInstance()-getValue(MOVEMENT_INVERT_MOTOR_Y),
ParameterList::getInstance()-getValue(MOVEMENT_INVERT_MOTOR_Z) };
bool endStInv[3] = { ParameterList::getInstance()-getValue(MOVEMENT_INVERT_ENDPOINTS_X),
ParameterList::getInstance()-getValue(MOVEMENT_INVERT_ENDPOINTS_Y),
ParameterList::getInstance()-getValue(MOVEMENT_INVERT_ENDPOINTS_Z) };
bool timeOut[3] = { ParameterList::getInstance()-getValue(MOVEMENT_TIMEOUT_X),
ParameterList::getInstance()-getValue(MOVEMENT_TIMEOUT_X),
ParameterList::getInstance()-getValue(MOVEMENT_TIMEOUT_X) };
bool homeAxis[3] = { homeX, homeY, homeZ };
bool home = homeX || homeY || homeZ;
@ -436,9 +467,20 @@ int StepperControl::moveAbsoluteConstant(long xDest, long yDest,
int error = 0;
if (maxStepsPerSecond == 0) {
maxStepsPerSecond = MOVEMENT_MAX_STEPS_PER_SECOND;
// if a speed is given in the command, use that instead of the config speed
if (xMaxSpd > 0 && xMaxSpd < speedMax[0]) {
speedMax[0] = xMaxSpd;
}
if (yMaxSpd > 0 && yMaxSpd < speedMax[1]) {
speedMax[1] = yMaxSpd;
}
if (zMaxSpd > 0 && zMaxSpd < speedMax[2]) {
speedMax[2] = zMaxSpd;
}
/*
Serial.print("R99 zdest ");
Serial.print(zDest);
@ -452,6 +494,8 @@ Serial.print("R99 current z ");
Serial.print(currentPoint[2]);
Serial.print("\n");
*/
// Prepare for movement
storeEndStops();
reportEndStops();
enableMotors(true);
@ -471,6 +515,8 @@ Serial.print("\n");
}
}
// Start movement
while (!movementDone) {
storeEndStops();
@ -484,7 +530,7 @@ Serial.print("\n");
Serial.print("\n");
}
*/
// Keek moving until destination reached or while moving home and end stop not reached
// Keep moving until destination reached or while moving home and end stop not reached
if (!pointReached(currentPoint, destinationPoint) || home) {
// Check eachh axis
for (int i = 0; i < 3; i++) {
@ -494,8 +540,8 @@ Serial.print("\n");
// axisSpeed = maxStepsPerSecond;
//if (i == 0) {
axisSpeed = calculateSpeed(sourcePoint[i],currentPoint[i],destinationPoint[i],
MOVEMENT_HOME_SPEED_S_P_S, MOVEMENT_MAX_STEPS_PER_SECOND, MOVEMENT_STEPS_ACC_DEC);
axisSpeed = calculateSpeed( sourcePoint[i],currentPoint[i],destinationPoint[i],
speedMax[i], speedMax[i], speedAcc[i]);
//}
if (homeAxis[i]){
// When home is active, the direction is fixed
@ -503,7 +549,7 @@ Serial.print("\n");
movementToHome = true;
if (currentPoint[i] == 0) {
// Go slow when theoretical end point reached but there is no end stop siganl
axisSpeed = MOVEMENT_HOME_SPEED_S_P_S;
axisSpeed = speedMin[i];
}
} else {
// For normal movement, move in direction of destination
@ -542,9 +588,15 @@ Serial.print(" home ");
Serial.print(homeAxis[i]);
Serial.print("\n");
*/
// If end stop reached, don't move anymore
if ((homeAxis[i] && !endStopAxisReached(i, false)) || (!homeAxis[i] && !endStopAxisReached(i, !movementToHome) && currentPoint[i] != destinationPoint[i] )) {
moving = true;
if (millis() - timeStart > timeOut[i] * MOVEMENT_SPEED_BASE_TIME) {
error = 1;
} else {
// If end stop reached, don't move anymore
if ((homeAxis[i] && !endStopAxisReached(i, false)) || (!homeAxis[i] && !endStopAxisReached(i, !movementToHome) && currentPoint[i] != destinationPoint[i] )) {
moving = true;
/*
Serial.print("R99 ");
Serial.print(" current ");
@ -555,24 +607,26 @@ Serial.print(" spd ");
Serial.print( 1000 / axisSpeed);
Serial.print("\n");
*/
// Only do a step every x milliseconds
if (currentMillis - lastStepMillis[i] >= MOVEMENT_SPEED_BASE_TIME / axisSpeed) {
if (homeAxis[i] && currentPoint[i] == 0) {
if (homeIsUp[i]) {
currentPoint[i] = -1;
} else {
currentPoint[i] = 1;
// Only do a step every x milliseconds
if (currentMillis - lastStepMillis[i] >= MOVEMENT_SPEED_BASE_TIME / axisSpeed) {
if (homeAxis[i] && currentPoint[i] == 0) {
if (homeIsUp[i]) {
currentPoint[i] = -1;
} else {
currentPoint[i] = 1;
}
}
}
//Serial.print("R99 ");
//Serial.print(" step ");
//Serial.print("\n");
/**/
step(i, currentPoint[i], 1, destinationPoint[i]);
stepMade = true;
lastStepMillis[i] = currentMillis;
step(i, currentPoint[i], 1, destinationPoint[i]);
stepMade = true;
lastStepMillis[i] = currentMillis;
}
}
}
}
@ -595,14 +649,11 @@ Serial.print("\n");
movementDone = true;
//Serial.print("R99 movement done\n");
}
// if (millis() - timeStart > 2 * 1000)
if (millis() - timeStart > MOVEMENT_TIMEOUT * MOVEMENT_SPEED_BASE_TIME)
{
//Serial.print("R99 movement timeout");
//Serial.print("\n");
movementDone = true;
error = 1;
}
// if (millis() - timeStart > MOVEMENT_TIMEOUT * MOVEMENT_SPEED_BASE_TIME)
// {
// movementDone = true;
// error = 1;
// }
delayMicroseconds(500);
}

View File

@ -14,6 +14,7 @@
#include "Config.h"
#include <stdio.h>
#include <stdlib.h>
#include "ParameterList.h"
class StepperControl {
public: