Formatting update

pull/68/head
Rick Carlino 2017-04-19 09:12:12 -05:00
parent 413f5c868f
commit 3d573dca0c
84 changed files with 4384 additions and 3742 deletions

View File

@ -13,7 +13,8 @@ const char msgQueueCode = 'Q';
CommandCodeEnum commandCodeEnum = CODE_UNDEFINED;
Command::Command(char * commandChar) {
Command::Command(char *commandChar)
{
char *charBuf = commandChar;
char *charPointer;
@ -21,175 +22,217 @@ Command::Command(char * commandChar) {
charPointer = strtok(charBuf, " \n\r");
if (charPointer[0] == 'G' || charPointer[0] == 'F') {
if (charPointer[0] == 'G' || charPointer[0] == 'F')
{
commandCodeEnum = getGCodeEnum(charPointer);
} else {
}
else
{
invalidCommand = true;
return;
}
while (charPointer != NULL) {
while (charPointer != NULL)
{
getParameter(charPointer);
charPointer = strtok(NULL, " \n\r");
}
}
CommandCodeEnum Command::getGCodeEnum(char* code) {
CommandCodeEnum Command::getGCodeEnum(char *code)
{
if (strcmp(code, "G0") == 0 || strcmp(code, "G00") == 0) {
if (strcmp(code, "G0") == 0 || strcmp(code, "G00") == 0)
{
return G00;
}
if (strcmp(code, "G1") == 0 || strcmp(code, "G01") == 0) {
if (strcmp(code, "G1") == 0 || strcmp(code, "G01") == 0)
{
return G01;
}
//if (strcmp(code, "F3") == 0 || strcmp(code, "F03") == 0) {
// return F03;
//}
if (strcmp(code, "F11") == 0) {
if (strcmp(code, "F11") == 0)
{
return F11;
}
if (strcmp(code, "F12") == 0) {
if (strcmp(code, "F12") == 0)
{
return F12;
}
if (strcmp(code, "F13") == 0) {
if (strcmp(code, "F13") == 0)
{
return F13;
}
if (strcmp(code, "F14") == 0) {
if (strcmp(code, "F14") == 0)
{
return F14;
}
if (strcmp(code, "F15") == 0) {
if (strcmp(code, "F15") == 0)
{
return F15;
}
if (strcmp(code, "F16") == 0) {
if (strcmp(code, "F16") == 0)
{
return F16;
}
if (strcmp(code, "F20") == 0) {
if (strcmp(code, "F20") == 0)
{
return F20;
}
if (strcmp(code, "F21") == 0) {
if (strcmp(code, "F21") == 0)
{
return F21;
}
if (strcmp(code, "F22") == 0) {
if (strcmp(code, "F22") == 0)
{
return F22;
}
if (strcmp(code, "F31") == 0) {
if (strcmp(code, "F31") == 0)
{
return F31;
}
if (strcmp(code, "F32") == 0) {
if (strcmp(code, "F32") == 0)
{
return F32;
}
if (strcmp(code, "F41") == 0) {
if (strcmp(code, "F41") == 0)
{
return F41;
}
if (strcmp(code, "F42") == 0) {
if (strcmp(code, "F42") == 0)
{
return F42;
}
if (strcmp(code, "F43") == 0) {
if (strcmp(code, "F43") == 0)
{
return F43;
}
if (strcmp(code, "F44") == 0) {
if (strcmp(code, "F44") == 0)
{
return F44;
}
if (strcmp(code, "F61") == 0) {
if (strcmp(code, "F61") == 0)
{
return F61;
}
if (strcmp(code, "F81") == 0) {
if (strcmp(code, "F81") == 0)
{
return F81;
}
if (strcmp(code, "F82") == 0) {
if (strcmp(code, "F82") == 0)
{
return F82;
}
if (strcmp(code, "F83") == 0) {
if (strcmp(code, "F83") == 0)
{
return F83;
}
if (strcmp(code, "F84") == 0) {
if (strcmp(code, "F84") == 0)
{
return F84;
}
return CODE_UNDEFINED;
}
double minusNotAllowed(double value) {
if(value < 0) {
double minusNotAllowed(double value)
{
if (value < 0)
{
return 0;
}
return value;
}
void Command::getParameter(char* charPointer) {
void Command::getParameter(char *charPointer)
{
//msgQueue = 24;
if (charPointer[0] == axisCodes[0] ){
if (charPointer[0] == axisCodes[0])
{
axisValue[0] = atof(charPointer + 1);
//msgQueue = 77;
}
if (charPointer[0] == axisCodes[1] ){
if (charPointer[0] == axisCodes[1])
{
axisValue[1] = atof(charPointer + 1);
}
if (charPointer[0] == axisCodes[2] ){
if (charPointer[0] == axisCodes[2])
{
axisValue[2] = atof(charPointer + 1);
}
if (charPointer[0] == axisSpeedCodes[0] ){
if (charPointer[0] == axisSpeedCodes[0])
{
axisSpeedValue[0] = atof(charPointer + 1);
}
if (charPointer[0] == axisSpeedCodes[1] ){
if (charPointer[0] == axisSpeedCodes[1])
{
axisSpeedValue[1] = atof(charPointer + 1);
}
if (charPointer[0] == axisSpeedCodes[2] ){
if (charPointer[0] == axisSpeedCodes[2])
{
axisSpeedValue[2] = atof(charPointer + 1);
}
if (charPointer[0] == speedCode ){
if (charPointer[0] == speedCode)
{
speedValue = atof(charPointer + 1);
}
if (charPointer[0] == parameterIdCode ){
if (charPointer[0] == parameterIdCode)
{
parameterId = atof(charPointer + 1);
}
if (charPointer[0] == parameterValueCode ){
if (charPointer[0] == parameterValueCode)
{
parameterValue = atof(charPointer + 1);
}
if (charPointer[0] == parameterValue2Code ){
if (charPointer[0] == parameterValue2Code)
{
parameterValue2 = atof(charPointer + 1);
}
if (charPointer[0] == elementCode ){
if (charPointer[0] == elementCode)
{
element = atof(charPointer + 1);
}
if (charPointer[0] == timeCode ){
if (charPointer[0] == timeCode)
{
time = atof(charPointer + 1);
}
if (charPointer[0] == modeCode ){
if (charPointer[0] == modeCode)
{
mode = atof(charPointer + 1);
}
if (charPointer[0] == msgQueueCode ){
if (charPointer[0] == msgQueueCode)
{
msgQueue = atof(charPointer + 1);
//msgQueue = 5;
}
}
void Command::print() {
void Command::print()
{
Serial.print("R99 Command with code: ");
Serial.print(commandCodeEnum);
Serial.print(", X: ");
@ -218,59 +261,73 @@ void Command::print() {
Serial.print("\r\n");
}
CommandCodeEnum Command::getCodeEnum() {
CommandCodeEnum Command::getCodeEnum()
{
return commandCodeEnum;
}
double Command::getX() {
double Command::getX()
{
return axisValue[0];
}
double Command::getY() {
double Command::getY()
{
return axisValue[1];
}
double Command::getZ() {
double Command::getZ()
{
return axisValue[2];
}
long Command::getA() {
long Command::getA()
{
return axisSpeedValue[0];
}
long Command::getB() {
long Command::getB()
{
return axisSpeedValue[1];
}
long Command::getC() {
long Command::getC()
{
return axisSpeedValue[2];
}
long Command::getP() {
long Command::getP()
{
return parameterId;
}
long Command::getV() {
long Command::getV()
{
return parameterValue;
}
long Command::getW() {
long Command::getW()
{
return parameterValue2;
}
long Command::getT() {
long Command::getT()
{
return time;
}
long Command::getE() {
long Command::getE()
{
return element;
}
long Command::getM() {
long Command::getM()
{
return mode;
}
long Command::getQ() {
long Command::getQ()
{
//msgQueue = 9876;
return msgQueue;
}

View File

@ -37,8 +37,10 @@ enum CommandCodeEnum
//#define NULL 0
class Command {
class Command
{
CommandCodeEnum codeEnum;
public:
// Command(String);
Command(char *commandChar);
@ -60,6 +62,7 @@ public:
long getQ();
void printQAndNewLine();
private:
CommandCodeEnum getGCodeEnum(char *code);
void getParameter(char *charPointer);
@ -74,7 +77,6 @@ private:
long time = 0;
long mode = 0;
long msgQueue = 0;
};
#endif /* COMMAND_H_ */

View File

@ -46,7 +46,6 @@ const int COMM_REPORT_CALIBRATE_STATUS_TO_HOME = 1;
const int COMM_REPORT_CALIBRATE_STATUS_TO_END = 2;
const int COMM_REPORT_CALIBRATE_STATUS_ERROR = -1;
const int MOVEMENT_INTERRUPT_SPEED = 200; // Interrupt cycle in micro seconds
const unsigned int MOVEMENT_SPEED_BASE_TIME = 2000;
@ -144,7 +143,6 @@ const long PIN_GUARD_5_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_5_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_5_ACTIVE_STATE_DEFAULT = 1;
const long STATUS_GENERAL_DEFAULT = 0;
const char SOFTWARE_VERSION[] = "GENESIS.V.01.08.EXPERIMENTAL\0";

View File

@ -15,14 +15,17 @@ unsigned int speed = 0;
bool endStopState[3][2];
long Q = 0;
CurrentState * CurrentState::getInstance() {
if (!instance) {
CurrentState *CurrentState::getInstance()
{
if (!instance)
{
instance = new CurrentState();
};
return instance;
};
CurrentState::CurrentState() {
CurrentState::CurrentState()
{
x = 0;
y = 0;
z = 0;
@ -30,40 +33,49 @@ CurrentState::CurrentState() {
Q = 0;
}
long CurrentState::getX() {
long CurrentState::getX()
{
return x;
}
long CurrentState::getY() {
long CurrentState::getY()
{
return y;
}
long CurrentState::getZ() {
long CurrentState::getZ()
{
return z;
}
long* CurrentState::getPoint() {
long *CurrentState::getPoint()
{
static long currentPoint[3] = {x, y, z};
return currentPoint;
}
void CurrentState::setX(long newX) {
void CurrentState::setX(long newX)
{
x = newX;
}
void CurrentState::setY(long newY) {
void CurrentState::setY(long newY)
{
y = newY;
}
void CurrentState::setZ(long newZ) {
void CurrentState::setZ(long newZ)
{
z = newZ;
}
void CurrentState::setEndStopState(unsigned int axis, unsigned int position, bool state) {
void CurrentState::setEndStopState(unsigned int axis, unsigned int position, bool state)
{
endStopState[axis][position] = state;
}
void CurrentState::storeEndStops() {
void CurrentState::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));
@ -72,7 +84,8 @@ void CurrentState::storeEndStops() {
CurrentState::getInstance()->setEndStopState(2, 1, digitalRead(Z_MAX_PIN));
}
void CurrentState::printPosition() {
void CurrentState::printPosition()
{
Serial.print("R82");
Serial.print(" X");
Serial.print(x);
@ -96,7 +109,8 @@ void CurrentState::printBool(bool value)
}
}
void CurrentState::printEndStops() {
void CurrentState::printEndStops()
{
Serial.print("R81");
Serial.print(" XA");
printBool(endStopState[0][0]);
@ -114,20 +128,24 @@ void CurrentState::printEndStops() {
printQAndNewLine();
}
void CurrentState::print() {
void CurrentState::print()
{
printPosition();
printEndStops();
}
void CurrentState::setQ(long q) {
void CurrentState::setQ(long q)
{
Q = q;
}
void CurrentState::resetQ() {
void CurrentState::resetQ()
{
Q = 0;
}
void CurrentState::printQAndNewLine() {
void CurrentState::printQAndNewLine()
{
Serial.print(" Q");
Serial.print(Q);
Serial.print("\r\n");

View File

@ -10,7 +10,8 @@
#include "Arduino.h"
#include "pins.h"
class CurrentState {
class CurrentState
{
public:
static CurrentState *getInstance();
long getX();
@ -35,7 +36,6 @@ private:
CurrentState();
CurrentState(CurrentState const &);
void operator=(CurrentState const &);
};
#endif /* CURRENTSTATE_H_ */

View File

@ -8,31 +8,34 @@
#include "F11Handler.h"
static F11Handler *instance;
F11Handler * F11Handler::getInstance() {
if (!instance) {
F11Handler *F11Handler::getInstance()
{
if (!instance)
{
instance = new F11Handler();
};
return instance;
}
;
};
F11Handler::F11Handler() {
F11Handler::F11Handler()
{
}
int F11Handler::execute(Command* command) {
int F11Handler::execute(Command *command)
{
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 HOME X\r\n");
}
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, true, false, false);
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
}

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class F11Handler : public GCodeHandler {
class F11Handler : public GCodeHandler
{
public:
static F11Handler *getInstance();
int execute(Command *);
private:
F11Handler();
F11Handler(F11Handler const &);
@ -27,4 +29,3 @@ private:
};
#endif /* F11HANDLER_H_ */

View File

@ -8,31 +8,34 @@
#include "F12Handler.h"
static F12Handler *instance;
F12Handler * F12Handler::getInstance() {
if (!instance) {
F12Handler *F12Handler::getInstance()
{
if (!instance)
{
instance = new F12Handler();
};
return instance;
}
;
};
F12Handler::F12Handler() {
F12Handler::F12Handler()
{
}
int F12Handler::execute(Command* command) {
int F12Handler::execute(Command *command)
{
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 HOME Y\r\n");
}
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, false, true, false);
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
}

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class F12Handler : public GCodeHandler {
class F12Handler : public GCodeHandler
{
public:
static F12Handler *getInstance();
int execute(Command *);
private:
F12Handler();
F12Handler(F12Handler const &);
@ -27,4 +29,3 @@ private:
};
#endif /* F12HANDLER_H_ */

View File

@ -8,31 +8,34 @@
#include "F13Handler.h"
static F13Handler *instance;
F13Handler * F13Handler::getInstance() {
if (!instance) {
F13Handler *F13Handler::getInstance()
{
if (!instance)
{
instance = new F13Handler();
};
return instance;
}
;
};
F13Handler::F13Handler() {
F13Handler::F13Handler()
{
}
int F13Handler::execute(Command* command) {
int F13Handler::execute(Command *command)
{
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 HOME Z\r\n");
}
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, false, false, true);
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
}

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class F13Handler : public GCodeHandler {
class F13Handler : public GCodeHandler
{
public:
static F13Handler *getInstance();
int execute(Command *);
private:
F13Handler();
F13Handler(F13Handler const &);
@ -27,4 +29,3 @@ private:
};
#endif /* F13HANDLER_H_ */

View File

@ -8,25 +8,28 @@
#include "F14Handler.h"
static F14Handler *instance;
F14Handler * F14Handler::getInstance() {
if (!instance) {
F14Handler *F14Handler::getInstance()
{
if (!instance)
{
instance = new F14Handler();
};
return instance;
}
;
};
F14Handler::F14Handler() {
F14Handler::F14Handler()
{
}
int F14Handler::execute(Command* command) {
int F14Handler::execute(Command *command)
{
int ret = 0;
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 CALIBRATE X\r\n");
}
@ -38,11 +41,10 @@ int F14Handler::execute(Command* command) {
}
*/
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
}

View File

@ -15,10 +15,12 @@
#include "Config.h"
#include "StepperControl.h"
class F14Handler : public GCodeHandler {
class F14Handler : public GCodeHandler
{
public:
static F14Handler *getInstance();
int execute(Command *);
private:
F14Handler();
F14Handler(F14Handler const &);
@ -28,5 +30,3 @@ private:
};
#endif /* F14HANDLER_H_ */

View File

@ -8,29 +8,33 @@
#include "F15Handler.h"
static F15Handler *instance;
F15Handler * F15Handler::getInstance() {
if (!instance) {
F15Handler *F15Handler::getInstance()
{
if (!instance)
{
instance = new F15Handler();
};
return instance;
}
;
};
F15Handler::F15Handler() {
F15Handler::F15Handler()
{
}
int F15Handler::execute(Command* command) {
int F15Handler::execute(Command *command)
{
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 HOME Z\r\n");
}
StepperControl::getInstance()->calibrateAxis(1);
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}

View File

@ -15,10 +15,12 @@
#include "Config.h"
#include "StepperControl.h"
class F15Handler : public GCodeHandler {
class F15Handler : public GCodeHandler
{
public:
static F15Handler *getInstance();
int execute(Command *);
private:
F15Handler();
F15Handler(F15Handler const &);
@ -28,5 +30,3 @@ private:
};
#endif /* F15HANDLER_H_ */

View File

@ -8,33 +8,35 @@
#include "F16Handler.h"
static F16Handler *instance;
F16Handler * F16Handler::getInstance() {
if (!instance) {
F16Handler *F16Handler::getInstance()
{
if (!instance)
{
instance = new F16Handler();
};
return instance;
}
;
};
F16Handler::F16Handler() {
F16Handler::F16Handler()
{
}
int F16Handler::execute(Command* command) {
int F16Handler::execute(Command *command)
{
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 HOME Z\r\n");
}
StepperControl::getInstance()->calibrateAxis(2);
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
}

View File

@ -15,10 +15,12 @@
#include "Config.h"
#include "StepperControl.h"
class F16Handler : public GCodeHandler {
class F16Handler : public GCodeHandler
{
public:
static F16Handler *getInstance();
int execute(Command *);
private:
F16Handler();
F16Handler(F16Handler const &);
@ -28,5 +30,3 @@ private:
};
#endif /* F16HANDLER_H_ */

View File

@ -7,21 +7,23 @@
#include "F20Handler.h"
static F20Handler *instance;
F20Handler * F20Handler::getInstance() {
if (!instance) {
F20Handler *F20Handler::getInstance()
{
if (!instance)
{
instance = new F20Handler();
};
return instance;
}
;
};
F20Handler::F20Handler() {
F20Handler::F20Handler()
{
}
int F20Handler::execute(Command* command) {
int F20Handler::execute(Command *command)
{
ParameterList::getInstance()->readAllValues();

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class F20Handler : public GCodeHandler {
class F20Handler : public GCodeHandler
{
public:
static F20Handler *getInstance();
int execute(Command *);
private:
F20Handler();
F20Handler(F20Handler const &);

View File

@ -7,21 +7,23 @@
#include "F21Handler.h"
static F21Handler *instance;
F21Handler * F21Handler::getInstance() {
if (!instance) {
F21Handler *F21Handler::getInstance()
{
if (!instance)
{
instance = new F21Handler();
};
return instance;
}
;
};
F21Handler::F21Handler() {
F21Handler::F21Handler()
{
}
int F21Handler::execute(Command* command) {
int F21Handler::execute(Command *command)
{
ParameterList::getInstance()->readValue(command->getP());

View File

@ -15,10 +15,12 @@
#include "StepperControl.h"
#include "ParameterList.h"
class F21Handler : public GCodeHandler {
class F21Handler : public GCodeHandler
{
public:
static F21Handler *getInstance();
int execute(Command *);
private:
F21Handler();
F21Handler(F21Handler const &);

View File

@ -7,21 +7,23 @@
#include "F22Handler.h"
static F22Handler *instance;
F22Handler * F22Handler::getInstance() {
if (!instance) {
F22Handler *F22Handler::getInstance()
{
if (!instance)
{
instance = new F22Handler();
};
return instance;
}
;
};
F22Handler::F22Handler() {
F22Handler::F22Handler()
{
}
int F22Handler::execute(Command* command) {
int F22Handler::execute(Command *command)
{
/*
Serial.print("R99");

View File

@ -15,10 +15,12 @@
#include "StepperControl.h"
#include "ParameterList.h"
class F22Handler : public GCodeHandler {
class F22Handler : public GCodeHandler
{
public:
static F22Handler *getInstance();
int execute(Command *);
private:
F22Handler();
F22Handler(F22Handler const &);

View File

@ -8,25 +8,25 @@
#include "F31Handler.h"
static F31Handler *instance;
F31Handler * F31Handler::getInstance() {
if (!instance) {
F31Handler *F31Handler::getInstance()
{
if (!instance)
{
instance = new F31Handler();
};
return instance;
}
;
};
F31Handler::F31Handler() {
F31Handler::F31Handler()
{
}
int F31Handler::execute(Command* command) {
int F31Handler::execute(Command *command)
{
StatusList::getInstance()->readValue(command->getP());
return 0;
}

View File

@ -16,10 +16,12 @@
#include "StepperControl.h"
#include "StatusList.h"
class F31Handler : public GCodeHandler {
class F31Handler : public GCodeHandler
{
public:
static F31Handler *getInstance();
int execute(Command *);
private:
F31Handler();
F31Handler(F31Handler const &);
@ -29,6 +31,3 @@ private:
};
#endif /* F31HANDLER_H_ */

View File

@ -8,25 +8,25 @@
#include "F32Handler.h"
static F32Handler *instance;
F32Handler * F32Handler::getInstance() {
if (!instance) {
F32Handler *F32Handler::getInstance()
{
if (!instance)
{
instance = new F32Handler();
};
return instance;
}
;
};
F32Handler::F32Handler() {
F32Handler::F32Handler()
{
}
int F32Handler::execute(Command* command) {
int F32Handler::execute(Command *command)
{
StatusList::getInstance()->readValue(command->getP());
return 0;
}

View File

@ -16,10 +16,12 @@
#include "StepperControl.h"
#include "StatusList.h"
class F32Handler : public GCodeHandler {
class F32Handler : public GCodeHandler
{
public:
static F32Handler *getInstance();
int execute(Command *);
private:
F32Handler();
F32Handler(F32Handler const &);
@ -29,6 +31,3 @@ private:
};
#endif /* F32HANDLER_H_ */

View File

@ -9,21 +9,23 @@
#include "F41Handler.h"
static F41Handler *instance;
F41Handler * F41Handler::getInstance() {
if (!instance) {
F41Handler *F41Handler::getInstance()
{
if (!instance)
{
instance = new F41Handler();
};
return instance;
}
;
};
F41Handler::F41Handler() {
F41Handler::F41Handler()
{
}
int F41Handler::execute(Command* command) {
int F41Handler::execute(Command *command)
{
PinControl::getInstance()->writeValue(command->getP(), command->getV(), command->getM());

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "PinControl.h"
class F41Handler : public GCodeHandler {
class F41Handler : public GCodeHandler
{
public:
static F41Handler *getInstance();
int execute(Command *);
private:
F41Handler();
F41Handler(F41Handler const &);
@ -25,9 +27,3 @@ private:
};
#endif /* F41HANDLER_H_ */

View File

@ -7,21 +7,23 @@
#include "F42Handler.h"
static F42Handler *instance;
F42Handler * F42Handler::getInstance() {
if (!instance) {
F42Handler *F42Handler::getInstance()
{
if (!instance)
{
instance = new F42Handler();
};
return instance;
}
;
};
F42Handler::F42Handler() {
F42Handler::F42Handler()
{
}
int F42Handler::execute(Command* command) {
int F42Handler::execute(Command *command)
{
PinControl::getInstance()->readValue(command->getP(), command->getM());

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "PinControl.h"
class F42Handler : public GCodeHandler {
class F42Handler : public GCodeHandler
{
public:
static F42Handler *getInstance();
int execute(Command *);
private:
F42Handler();
F42Handler(F42Handler const &);
@ -25,9 +27,3 @@ private:
};
#endif /* F42HANDLER_H_ */

View File

@ -9,30 +9,25 @@
#include "F43Handler.h"
static F43Handler *instance;
F43Handler * F43Handler::getInstance() {
if (!instance) {
F43Handler *F43Handler::getInstance()
{
if (!instance)
{
instance = new F43Handler();
};
return instance;
}
;
};
F43Handler::F43Handler() {
F43Handler::F43Handler()
{
}
int F43Handler::execute(Command* command) {
int F43Handler::execute(Command *command)
{
PinControl::getInstance()->setMode(command->getP(), command->getM());
return 0;
}

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "PinControl.h"
class F43Handler : public GCodeHandler {
class F43Handler : public GCodeHandler
{
public:
static F43Handler *getInstance();
int execute(Command *);
private:
F43Handler();
F43Handler(F43Handler const &);

View File

@ -9,21 +9,23 @@
#include "F44Handler.h"
static F44Handler *instance;
F44Handler * F44Handler::getInstance() {
if (!instance) {
F44Handler *F44Handler::getInstance()
{
if (!instance)
{
instance = new F44Handler();
};
return instance;
}
;
};
F44Handler::F44Handler() {
F44Handler::F44Handler()
{
}
int F44Handler::execute(Command* command) {
int F44Handler::execute(Command *command)
{
PinControl::getInstance()->writePulse(command->getP(), command->getV(), command->getW(), command->getT(), command->getM());

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "PinControl.h"
class F44Handler : public GCodeHandler {
class F44Handler : public GCodeHandler
{
public:
static F44Handler *getInstance();
int execute(Command *);
private:
F44Handler();
F44Handler(F44Handler const &);
@ -25,6 +27,3 @@ private:
};
#endif /* F44HANDLER_H_ */

View File

@ -9,21 +9,23 @@
#include "F61Handler.h"
static F61Handler *instance;
F61Handler * F61Handler::getInstance() {
if (!instance) {
F61Handler *F61Handler::getInstance()
{
if (!instance)
{
instance = new F61Handler();
};
return instance;
}
;
};
F61Handler::F61Handler() {
F61Handler::F61Handler()
{
}
int F61Handler::execute(Command* command) {
int F61Handler::execute(Command *command)
{
ServoControl::getInstance()->setAngle(command->getP(), command->getV());

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "ServoControl.h"
class F61Handler : public GCodeHandler {
class F61Handler : public GCodeHandler
{
public:
static F61Handler *getInstance();
int execute(Command *);
private:
F61Handler();
F61Handler(F61Handler const &);
@ -25,9 +27,3 @@ private:
};
#endif /* F61HANDLER_H_ */

View File

@ -9,25 +9,28 @@
#include "F81Handler.h"
static F81Handler *instance;
F81Handler * F81Handler::getInstance() {
if (!instance) {
F81Handler *F81Handler::getInstance()
{
if (!instance)
{
instance = new F81Handler();
};
return instance;
}
;
};
F81Handler::F81Handler() {
F81Handler::F81Handler()
{
}
int F81Handler::execute(Command* command) {
int F81Handler::execute(Command *command)
{
Serial.print("home\r\n");
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 Report end stops\r\n");
}
@ -41,8 +44,5 @@ Serial.print("home\r\n");
PinControl::getInstance()->readValue(10, 0);
PinControl::getInstance()->readValue(13, 0);
return 0;
}

View File

@ -15,10 +15,12 @@
#include "StepperControl.h"
#include "PinControl.h"
class F81Handler : public GCodeHandler {
class F81Handler : public GCodeHandler
{
public:
static F81Handler *getInstance();
int execute(Command *);
private:
F81Handler();
F81Handler(F81Handler const &);
@ -28,4 +30,3 @@ private:
};
#endif /* F81HANDLER_H_ */

View File

@ -9,23 +9,26 @@
#include "F82Handler.h"
static F82Handler *instance;
F82Handler * F82Handler::getInstance() {
if (!instance) {
F82Handler *F82Handler::getInstance()
{
if (!instance)
{
instance = new F82Handler();
};
return instance;
}
;
};
F82Handler::F82Handler() {
F82Handler::F82Handler()
{
}
int F82Handler::execute(Command* command) {
int F82Handler::execute(Command *command)
{
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 Report current position\r\n");
}
@ -33,6 +36,3 @@ int F82Handler::execute(Command* command) {
return 0;
}

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class F82Handler : public GCodeHandler {
class F82Handler : public GCodeHandler
{
public:
static F82Handler *getInstance();
int execute(Command *);
private:
F82Handler();
F82Handler(F82Handler const &);
@ -27,4 +29,3 @@ private:
};
#endif /* F82HANDLER_H_ */

View File

@ -9,23 +9,26 @@
#include "F83Handler.h"
static F83Handler *instance;
F83Handler * F83Handler::getInstance() {
if (!instance) {
F83Handler *F83Handler::getInstance()
{
if (!instance)
{
instance = new F83Handler();
};
return instance;
}
;
};
F83Handler::F83Handler() {
F83Handler::F83Handler()
{
}
int F83Handler::execute(Command* command) {
int F83Handler::execute(Command *command)
{
if (LOGGING) {
if (LOGGING)
{
Serial.print("R99 Report server version\r\n");
}
@ -36,6 +39,3 @@ int F83Handler::execute(Command* command) {
return 0;
}

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class F83Handler : public GCodeHandler {
class F83Handler : public GCodeHandler
{
public:
static F83Handler *getInstance();
int execute(Command *);
private:
F83Handler();
F83Handler(F83Handler const &);
@ -27,4 +29,3 @@ private:
};
#endif /* F83HANDLER_H_ */

View File

@ -7,26 +7,26 @@
#include "G00Handler.h"
static G00Handler *instance;
G00Handler * G00Handler::getInstance() {
if (!instance) {
G00Handler *G00Handler::getInstance()
{
if (!instance)
{
instance = new G00Handler();
};
return instance;
}
;
};
G00Handler::G00Handler() {
G00Handler::G00Handler()
{
}
int G00Handler::execute(Command* command) {
int G00Handler::execute(Command *command)
{
// Serial.print("G00 was here\r\n");
// Serial.print("R99");
// Serial.print(" X ");
// Serial.print(command->getX());
@ -42,15 +42,13 @@ int G00Handler::execute(Command* command) {
// Serial.print(command->getC());
// Serial.print("\r\n");
StepperControl::getInstance()->moveToCoords
(
StepperControl::getInstance()->moveToCoords(
command->getX(), command->getY(), command->getZ(),
command->getA(), command->getB(), command->getC(),
false, false, false
);
false, false, false);
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class G00Handler : public GCodeHandler {
class G00Handler : public GCodeHandler
{
public:
static G00Handler *getInstance();
int execute(Command *);
private:
G00Handler();
G00Handler(G00Handler const &);

View File

@ -7,28 +7,31 @@
#include "G28Handler.h"
static G28Handler *instance;
G28Handler * G28Handler::getInstance() {
if (!instance) {
G28Handler *G28Handler::getInstance()
{
if (!instance)
{
instance = new G28Handler();
};
return instance;
}
;
};
G28Handler::G28Handler() {
G28Handler::G28Handler()
{
}
int G28Handler::execute(Command* command) {
int G28Handler::execute(Command *command)
{
//Serial.print("home\r\n");
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, false, false, true);
StepperControl::getInstance()->moveToCoords(0, 0, 0, 0, 0, 0, true, true, false);
//StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,HOME_MOVEMENT_SPEED_S_P_S,true);
if (LOGGING) {
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;

View File

@ -14,10 +14,12 @@
#include "Config.h"
#include "StepperControl.h"
class G28Handler : public GCodeHandler {
class G28Handler : public GCodeHandler
{
public:
static G28Handler *getInstance();
int execute(Command *);
private:
G28Handler();
G28Handler(G28Handler const &);

View File

@ -7,13 +7,15 @@
#include "GCodeHandler.h"
GCodeHandler::GCodeHandler() {
GCodeHandler::GCodeHandler()
{
}
GCodeHandler::~GCodeHandler() {
GCodeHandler::~GCodeHandler()
{
}
int GCodeHandler::execute(Command*) {
int GCodeHandler::execute(Command *)
{
return -1;
}

View File

@ -9,7 +9,8 @@
#define GCODEHANDLER_H_
#include "Command.h"
class GCodeHandler {
class GCodeHandler
{
public:
GCodeHandler();
virtual ~GCodeHandler();

View File

@ -9,26 +9,28 @@
#include "GCodeProcessor.h"
#include "CurrentState.h"
GCodeProcessor::GCodeProcessor() {
GCodeProcessor::GCodeProcessor()
{
}
GCodeProcessor::~GCodeProcessor() {
GCodeProcessor::~GCodeProcessor()
{
}
void GCodeProcessor::printCommandLog(Command* command) {
void GCodeProcessor::printCommandLog(Command *command)
{
Serial.print("command == NULL: ");
Serial.println("\r\n");
}
int GCodeProcessor::execute(Command* command) {
int GCodeProcessor::execute(Command *command)
{
int execution = 0;
long Q = command->getQ();
CurrentState::getInstance()->setQ(Q);
// Do not execute the command when the config complete parameter is not
// set by the raspberry pi and it's asked to do a move command
@ -53,15 +55,19 @@ int GCodeProcessor::execute(Command* command) {
// Return error when no command or invalid command is found
if(command == NULL) {
if(LOGGING) {
if (command == NULL)
{
if (LOGGING)
{
printCommandLog(command);
}
return -1;
}
if(command->getCodeEnum() == CODE_UNDEFINED) {
if(LOGGING) {
if (command->getCodeEnum() == CODE_UNDEFINED)
{
if (LOGGING)
{
printCommandLog(command);
}
return -1;
@ -71,7 +77,8 @@ int GCodeProcessor::execute(Command* command) {
GCodeHandler *handler = getGCodeHandler(command->getCodeEnum());
if(handler == NULL) {
if (handler == NULL)
{
Serial.println("R99 handler == NULL\r\n");
return -1;
}
@ -82,10 +89,13 @@ int GCodeProcessor::execute(Command* command) {
CurrentState::getInstance()->printQAndNewLine();
execution = handler->execute(command);
if(execution == 0) {
if (execution == 0)
{
Serial.print(COMM_REPORT_CMD_DONE);
CurrentState::getInstance()->printQAndNewLine();
} else {
}
else
{
Serial.print(COMM_REPORT_CMD_ERROR);
CurrentState::getInstance()->printQAndNewLine();
}
@ -94,47 +104,104 @@ int GCodeProcessor::execute(Command* command) {
return execution;
};
GCodeHandler* GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum) {
GCodeHandler *GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum)
{
GCodeHandler *handler = NULL;
// These are if statements so they can be disabled as test
// Usefull when running into memory issues again
if (codeEnum == G00)
{
handler = G00Handler::getInstance();
}
if (codeEnum == G00) {handler = G00Handler::getInstance();}
if (codeEnum == G28)
{
handler = G28Handler::getInstance();
}
if (codeEnum == G28) {handler = G28Handler::getInstance();}
if (codeEnum == F11)
{
handler = F11Handler::getInstance();
}
if (codeEnum == F12)
{
handler = F12Handler::getInstance();
}
if (codeEnum == F13)
{
handler = F13Handler::getInstance();
}
if (codeEnum == F11) {handler = F11Handler::getInstance();}
if (codeEnum == F12) {handler = F12Handler::getInstance();}
if (codeEnum == F13) {handler = F13Handler::getInstance();}
if (codeEnum == F14)
{
handler = F14Handler::getInstance();
}
if (codeEnum == F15)
{
handler = F15Handler::getInstance();
}
if (codeEnum == F16)
{
handler = F16Handler::getInstance();
}
if (codeEnum == F14) {handler = F14Handler::getInstance();}
if (codeEnum == F15) {handler = F15Handler::getInstance();}
if (codeEnum == F16) {handler = F16Handler::getInstance();}
if (codeEnum == F20) {handler = F20Handler::getInstance();}
if (codeEnum == F21) {handler = F21Handler::getInstance();}
if (codeEnum == F22) {handler = F22Handler::getInstance();}
if (codeEnum == F20)
{
handler = F20Handler::getInstance();
}
if (codeEnum == F21)
{
handler = F21Handler::getInstance();
}
if (codeEnum == F22)
{
handler = F22Handler::getInstance();
}
// if (codeEnum == F31) {handler = F31Handler::getInstance();}
// if (codeEnum == F32) {handler = F32Handler::getInstance();}
if (codeEnum == F41) {handler = F41Handler::getInstance();}
if (codeEnum == F42) {handler = F42Handler::getInstance();}
if (codeEnum == F43) {handler = F43Handler::getInstance();}
if (codeEnum == F44) {handler = F44Handler::getInstance();}
if (codeEnum == F41)
{
handler = F41Handler::getInstance();
}
if (codeEnum == F42)
{
handler = F42Handler::getInstance();
}
if (codeEnum == F43)
{
handler = F43Handler::getInstance();
}
if (codeEnum == F44)
{
handler = F44Handler::getInstance();
}
if (codeEnum == F61) {handler = F61Handler::getInstance();}
if (codeEnum == F81) {handler = F81Handler::getInstance();}
if (codeEnum == F82) {handler = F82Handler::getInstance();}
if (codeEnum == F83) {handler = F83Handler::getInstance();}
if (codeEnum == F84) {handler = F84Handler::getInstance();}
if (codeEnum == F61)
{
handler = F61Handler::getInstance();
}
if (codeEnum == F81)
{
handler = F81Handler::getInstance();
}
if (codeEnum == F82)
{
handler = F82Handler::getInstance();
}
if (codeEnum == F83)
{
handler = F83Handler::getInstance();
}
if (codeEnum == F84)
{
handler = F84Handler::getInstance();
}
return handler;
}

View File

@ -42,13 +42,16 @@
#include "F83Handler.h"
#include "F84Handler.h"
class GCodeProcessor {
class GCodeProcessor
{
public:
GCodeProcessor();
virtual ~GCodeProcessor();
int execute(Command *command);
protected:
GCodeHandler *getGCodeHandler(CommandCodeEnum);
private:
void printCommandLog(Command *);
};

View File

@ -4,14 +4,17 @@
static ParameterList *instanceParam;
int paramValues[PARAM_NR_OF_PARAMS];
ParameterList * ParameterList::getInstance() {
if (!instanceParam) {
ParameterList *ParameterList::getInstance()
{
if (!instanceParam)
{
instanceParam = new ParameterList();
};
return instanceParam;
}
ParameterList::ParameterList() {
ParameterList::ParameterList()
{
// at the first boot, load default parameters and set the parameter version
// so during subsequent boots the values are just loaded from eeprom
// unless the eeprom is disabled with a parameter
@ -19,10 +22,13 @@ ParameterList::ParameterList() {
int paramChangeNr = 0;
int paramVersion = readValueEeprom(0);
if (paramVersion <= 0) {
if (paramVersion <= 0)
{
setAllValuesToDefault();
writeAllValuesToEeprom();
} else {
}
else
{
//if (readValueEeprom(PARAM_USE_EEPROM) == 1) {
readAllValuesFromEeprom();
//} else {
@ -33,10 +39,12 @@ ParameterList::ParameterList() {
// ===== Interface functions for the raspberry pi =====
int ParameterList::readValue(int id) {
int ParameterList::readValue(int id)
{
// Check if the value is an existing parameter
if (validParam(id)) {
if (validParam(id))
{
// Retrieve the value from memory
int value = paramValues[id];
@ -50,32 +58,39 @@ int ParameterList::readValue(int id) {
Serial.print(value);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
} else {
}
else
{
Serial.print("R99 Error: invalid parameter id\r\n");
}
return 0;
}
int ParameterList::writeValue(int id, int value) {
int ParameterList::writeValue(int id, int value)
{
if (paramChangeNr < 9999) {
if (paramChangeNr < 9999)
{
paramChangeNr++;
} else {
}
else
{
paramChangeNr = 0;
}
// Check if the value is a valid parameter
if (validParam(id)) {
if (validParam(id))
{
// Store the value in memory
paramValues[id] = value;
writeValueEeprom(id, value);
} else {
}
else
{
Serial.print("R99 Error: invalid parameter id\r\n");
}
/*
// Debugging output
Serial.print("R99");
@ -100,36 +115,40 @@ int ParameterList::writeValue(int id, int value) {
return 0;
}
void ParameterList::sendConfigToModules() {
void ParameterList::sendConfigToModules()
{
// Trigger other modules to load the new values
PinGuard::getInstance()->loadConfig();
}
int ParameterList::readAllValues() {
int ParameterList::readAllValues()
{
// Make a dump of all values
// Check if it's a valid value to keep the junk out of the list
for (int i=0; i < PARAM_NR_OF_PARAMS; i++) {
if (validParam(i)) {
for (int i = 0; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i))
{
readValue(i);
}
}
}
int ParameterList::getValue(int id) {
int ParameterList::getValue(int id)
{
return paramValues[id];
}
int ParameterList::paramChangeNumber() {
int ParameterList::paramChangeNumber()
{
return paramChangeNr;
}
// ===== eeprom handling ====
int ParameterList::readValueEeprom(int id) {
int ParameterList::readValueEeprom(int id)
{
// Assume all values are ints and calculate address for that
int address = id * 2;
@ -142,7 +161,8 @@ int ParameterList::readValueEeprom(int id) {
return ((two << 0) & 0xFF) + ((one << 8) & 0xFFFF);
}
int ParameterList::writeValueEeprom(int id, int value) {
int ParameterList::writeValueEeprom(int id, int value)
{
// Assume all values are ints and calculate address for that
int address = id * 2;
@ -159,12 +179,16 @@ int ParameterList::writeValueEeprom(int id, int value) {
return 0;
}
int ParameterList::readAllValuesFromEeprom() {
int ParameterList::readAllValuesFromEeprom()
{
// Write all existing values to eeprom
for (int i=0; i < PARAM_NR_OF_PARAMS; i++) {
if (validParam(i)) {
for (int i = 0; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i))
{
paramValues[i] = readValueEeprom(i);
if (paramValues[i] == -1) {
if (paramValues[i] == -1)
{
// When parameters are still on default,
// load a good value and save it
loadDefaultValue(i);
@ -174,11 +198,13 @@ int ParameterList::readAllValuesFromEeprom() {
}
}
int ParameterList::writeAllValuesToEeprom() {
int ParameterList::writeAllValuesToEeprom()
{
// Write all existing values to eeprom
for (int i = 0; i < 150; i++)
{
if (validParam(i)) {
if (validParam(i))
{
writeValueEeprom(i, paramValues[i]);
}
}
@ -186,105 +212,231 @@ int ParameterList::writeAllValuesToEeprom() {
// ==== parameter valdation and defaults
int ParameterList::setAllValuesToDefault() {
int ParameterList::setAllValuesToDefault()
{
// Copy default values to the memory values
for (int i = 0; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i)) {
if (validParam(i))
{
loadDefaultValue(i);
}
}
}
void ParameterList::loadDefaultValue(int id) {
void ParameterList::loadDefaultValue(int id)
{
switch (id)
{
case PARAM_VERSION : paramValues[id] = PARAM_VERSION_DEFAULT; break;
case PARAM_TEST : paramValues[id] = PARAM_TEST_DEFAULT; break;
case PARAM_CONFIG_OK : paramValues[id] = PARAM_CONFIG_OK_DEFAULT; break;
case PARAM_USE_EEPROM : paramValues[id] = PARAM_USE_EEPROM; break;
case PARAM_VERSION:
paramValues[id] = PARAM_VERSION_DEFAULT;
break;
case PARAM_TEST:
paramValues[id] = PARAM_TEST_DEFAULT;
break;
case PARAM_CONFIG_OK:
paramValues[id] = PARAM_CONFIG_OK_DEFAULT;
break;
case PARAM_USE_EEPROM:
paramValues[id] = PARAM_USE_EEPROM;
break;
case MOVEMENT_TIMEOUT_X : paramValues[id] = MOVEMENT_TIMEOUT_X_DEFAULT; break;
case MOVEMENT_TIMEOUT_Y : paramValues[id] = MOVEMENT_TIMEOUT_Y_DEFAULT; break;
case MOVEMENT_TIMEOUT_Z : paramValues[id] = MOVEMENT_TIMEOUT_Z_DEFAULT; break;
case MOVEMENT_TIMEOUT_X:
paramValues[id] = MOVEMENT_TIMEOUT_X_DEFAULT;
break;
case MOVEMENT_TIMEOUT_Y:
paramValues[id] = MOVEMENT_TIMEOUT_Y_DEFAULT;
break;
case MOVEMENT_TIMEOUT_Z:
paramValues[id] = MOVEMENT_TIMEOUT_Z_DEFAULT;
break;
case MOVEMENT_INVERT_ENDPOINTS_X : paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT; break;
case MOVEMENT_INVERT_ENDPOINTS_Y : paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT; break;
case MOVEMENT_INVERT_ENDPOINTS_Z : paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT; break;
case MOVEMENT_INVERT_ENDPOINTS_X:
paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT;
break;
case MOVEMENT_INVERT_ENDPOINTS_Y:
paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT;
break;
case MOVEMENT_INVERT_ENDPOINTS_Z:
paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT;
break;
case MOVEMENT_ENABLE_ENDPOINTS_X : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT; break;
case MOVEMENT_ENABLE_ENDPOINTS_Y : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT; break;
case MOVEMENT_ENABLE_ENDPOINTS_Z : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT; break;
case MOVEMENT_ENABLE_ENDPOINTS_X:
paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT;
break;
case MOVEMENT_ENABLE_ENDPOINTS_Y:
paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT;
break;
case MOVEMENT_ENABLE_ENDPOINTS_Z:
paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT;
break;
case MOVEMENT_INVERT_MOTOR_X : paramValues[id] = MOVEMENT_INVERT_MOTOR_X_DEFAULT; break;
case MOVEMENT_INVERT_MOTOR_Y : paramValues[id] = MOVEMENT_INVERT_MOTOR_Y_DEFAULT; break;
case MOVEMENT_INVERT_MOTOR_Z : paramValues[id] = MOVEMENT_INVERT_MOTOR_Z_DEFAULT; break;
case MOVEMENT_INVERT_MOTOR_X:
paramValues[id] = MOVEMENT_INVERT_MOTOR_X_DEFAULT;
break;
case MOVEMENT_INVERT_MOTOR_Y:
paramValues[id] = MOVEMENT_INVERT_MOTOR_Y_DEFAULT;
break;
case MOVEMENT_INVERT_MOTOR_Z:
paramValues[id] = MOVEMENT_INVERT_MOTOR_Z_DEFAULT;
break;
case MOVEMENT_SECONDARY_MOTOR_X : paramValues[id] = MOVEMENT_SECONDARY_MOTOR_X_DEFAULT; break;
case MOVEMENT_SECONDARY_MOTOR_INVERT_X : paramValues[id] = MOVEMENT_SECONDARY_MOTOR_INVERT_X_DEFAULT; break;
case MOVEMENT_SECONDARY_MOTOR_X:
paramValues[id] = MOVEMENT_SECONDARY_MOTOR_X_DEFAULT;
break;
case MOVEMENT_SECONDARY_MOTOR_INVERT_X:
paramValues[id] = MOVEMENT_SECONDARY_MOTOR_INVERT_X_DEFAULT;
break;
case MOVEMENT_STEPS_ACC_DEC_X : paramValues[id] = MOVEMENT_STEPS_ACC_DEC_X_DEFAULT; break;
case MOVEMENT_STEPS_ACC_DEC_Y : paramValues[id] = MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT; break;
case MOVEMENT_STEPS_ACC_DEC_Z : paramValues[id] = MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT; break;
case MOVEMENT_STEPS_ACC_DEC_X:
paramValues[id] = MOVEMENT_STEPS_ACC_DEC_X_DEFAULT;
break;
case MOVEMENT_STEPS_ACC_DEC_Y:
paramValues[id] = MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT;
break;
case MOVEMENT_STEPS_ACC_DEC_Z:
paramValues[id] = MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT;
break;
case MOVEMENT_HOME_UP_X : paramValues[id] = MOVEMENT_HOME_UP_X_DEFAULT; break;
case MOVEMENT_HOME_UP_Y : paramValues[id] = MOVEMENT_HOME_UP_Y_DEFAULT; break;
case MOVEMENT_HOME_UP_Z : paramValues[id] = MOVEMENT_HOME_UP_Z_DEFAULT; break;
case MOVEMENT_HOME_UP_X:
paramValues[id] = MOVEMENT_HOME_UP_X_DEFAULT;
break;
case MOVEMENT_HOME_UP_Y:
paramValues[id] = MOVEMENT_HOME_UP_Y_DEFAULT;
break;
case MOVEMENT_HOME_UP_Z:
paramValues[id] = MOVEMENT_HOME_UP_Z_DEFAULT;
break;
case MOVEMENT_MIN_SPD_X : paramValues[id] = MOVEMENT_MIN_SPD_X_DEFAULT; break;
case MOVEMENT_MIN_SPD_Y : paramValues[id] = MOVEMENT_MIN_SPD_Y_DEFAULT; break;
case MOVEMENT_MIN_SPD_Z : paramValues[id] = MOVEMENT_MIN_SPD_Z_DEFAULT; break;
case MOVEMENT_MIN_SPD_X:
paramValues[id] = MOVEMENT_MIN_SPD_X_DEFAULT;
break;
case MOVEMENT_MIN_SPD_Y:
paramValues[id] = MOVEMENT_MIN_SPD_Y_DEFAULT;
break;
case MOVEMENT_MIN_SPD_Z:
paramValues[id] = MOVEMENT_MIN_SPD_Z_DEFAULT;
break;
case MOVEMENT_MAX_SPD_X : paramValues[id] = MOVEMENT_MAX_SPD_X_DEFAULT; break;
case MOVEMENT_MAX_SPD_Y : paramValues[id] = MOVEMENT_MAX_SPD_Y_DEFAULT; break;
case MOVEMENT_MAX_SPD_Z : paramValues[id] = MOVEMENT_MAX_SPD_Z_DEFAULT; break;
case MOVEMENT_MAX_SPD_X:
paramValues[id] = MOVEMENT_MAX_SPD_X_DEFAULT;
break;
case MOVEMENT_MAX_SPD_Y:
paramValues[id] = MOVEMENT_MAX_SPD_Y_DEFAULT;
break;
case MOVEMENT_MAX_SPD_Z:
paramValues[id] = MOVEMENT_MAX_SPD_Z_DEFAULT;
break;
case ENCODER_ENABLED_X : paramValues[id] = ENCODER_ENABLED_X_DEFAULT; break;
case ENCODER_ENABLED_Y : paramValues[id] = ENCODER_ENABLED_Y_DEFAULT; break;
case ENCODER_ENABLED_Z : paramValues[id] = ENCODER_ENABLED_Z_DEFAULT; break;
case ENCODER_ENABLED_X:
paramValues[id] = ENCODER_ENABLED_X_DEFAULT;
break;
case ENCODER_ENABLED_Y:
paramValues[id] = ENCODER_ENABLED_Y_DEFAULT;
break;
case ENCODER_ENABLED_Z:
paramValues[id] = ENCODER_ENABLED_Z_DEFAULT;
break;
case ENCODER_TYPE_X : paramValues[id] = ENCODER_TYPE_X_DEFAULT; break;
case ENCODER_TYPE_Y : paramValues[id] = ENCODER_TYPE_Y_DEFAULT; break;
case ENCODER_TYPE_Z : paramValues[id] = ENCODER_TYPE_Z_DEFAULT; break;
case ENCODER_TYPE_X:
paramValues[id] = ENCODER_TYPE_X_DEFAULT;
break;
case ENCODER_TYPE_Y:
paramValues[id] = ENCODER_TYPE_Y_DEFAULT;
break;
case ENCODER_TYPE_Z:
paramValues[id] = ENCODER_TYPE_Z_DEFAULT;
break;
case ENCODER_MISSED_STEPS_MAX_X : paramValues[id] = ENCODER_MISSED_STEPS_MAX_X_DEFAULT; break;
case ENCODER_MISSED_STEPS_MAX_Y : paramValues[id] = ENCODER_MISSED_STEPS_MAX_Y_DEFAULT; break;
case ENCODER_MISSED_STEPS_MAX_Z : paramValues[id] = ENCODER_MISSED_STEPS_MAX_Z_DEFAULT; break;
case ENCODER_MISSED_STEPS_MAX_X:
paramValues[id] = ENCODER_MISSED_STEPS_MAX_X_DEFAULT;
break;
case ENCODER_MISSED_STEPS_MAX_Y:
paramValues[id] = ENCODER_MISSED_STEPS_MAX_Y_DEFAULT;
break;
case ENCODER_MISSED_STEPS_MAX_Z:
paramValues[id] = ENCODER_MISSED_STEPS_MAX_Z_DEFAULT;
break;
case ENCODER_SCALING_X : paramValues[id] = ENCODER_SCALING_X_DEFAULT; break;
case ENCODER_SCALING_Y : paramValues[id] = ENCODER_SCALING_Y_DEFAULT; break;
case ENCODER_SCALING_Z : paramValues[id] = ENCODER_SCALING_Z_DEFAULT; break;
case ENCODER_SCALING_X:
paramValues[id] = ENCODER_SCALING_X_DEFAULT;
break;
case ENCODER_SCALING_Y:
paramValues[id] = ENCODER_SCALING_Y_DEFAULT;
break;
case ENCODER_SCALING_Z:
paramValues[id] = ENCODER_SCALING_Z_DEFAULT;
break;
case ENCODER_MISSED_STEPS_DECAY_X : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_X_DEFAULT; break;
case ENCODER_MISSED_STEPS_DECAY_Y : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT; break;
case ENCODER_MISSED_STEPS_DECAY_Z : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT; break;
case ENCODER_MISSED_STEPS_DECAY_X:
paramValues[id] = ENCODER_MISSED_STEPS_DECAY_X_DEFAULT;
break;
case ENCODER_MISSED_STEPS_DECAY_Y:
paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT;
break;
case ENCODER_MISSED_STEPS_DECAY_Z:
paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT;
break;
case PIN_GUARD_1_PIN_NR : paramValues[id] = PIN_GUARD_1_PIN_NR_DEFAULT; break;
case PIN_GUARD_1_TIME_OUT : paramValues[id] = PIN_GUARD_1_TIME_OUT_DEFAULT; break;
case PIN_GUARD_1_ACTIVE_STATE : paramValues[id] = PIN_GUARD_1_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_1_PIN_NR:
paramValues[id] = PIN_GUARD_1_PIN_NR_DEFAULT;
break;
case PIN_GUARD_1_TIME_OUT:
paramValues[id] = PIN_GUARD_1_TIME_OUT_DEFAULT;
break;
case PIN_GUARD_1_ACTIVE_STATE:
paramValues[id] = PIN_GUARD_1_ACTIVE_STATE_DEFAULT;
break;
case PIN_GUARD_2_PIN_NR : paramValues[id] = PIN_GUARD_2_PIN_NR_DEFAULT; break;
case PIN_GUARD_2_TIME_OUT : paramValues[id] = PIN_GUARD_2_TIME_OUT_DEFAULT; break;
case PIN_GUARD_2_ACTIVE_STATE : paramValues[id] = PIN_GUARD_2_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_2_PIN_NR:
paramValues[id] = PIN_GUARD_2_PIN_NR_DEFAULT;
break;
case PIN_GUARD_2_TIME_OUT:
paramValues[id] = PIN_GUARD_2_TIME_OUT_DEFAULT;
break;
case PIN_GUARD_2_ACTIVE_STATE:
paramValues[id] = PIN_GUARD_2_ACTIVE_STATE_DEFAULT;
break;
case PIN_GUARD_3_PIN_NR : paramValues[id] = PIN_GUARD_3_PIN_NR_DEFAULT; break;
case PIN_GUARD_3_TIME_OUT : paramValues[id] = PIN_GUARD_3_TIME_OUT_DEFAULT; break;
case PIN_GUARD_3_ACTIVE_STATE : paramValues[id] = PIN_GUARD_3_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_3_PIN_NR:
paramValues[id] = PIN_GUARD_3_PIN_NR_DEFAULT;
break;
case PIN_GUARD_3_TIME_OUT:
paramValues[id] = PIN_GUARD_3_TIME_OUT_DEFAULT;
break;
case PIN_GUARD_3_ACTIVE_STATE:
paramValues[id] = PIN_GUARD_3_ACTIVE_STATE_DEFAULT;
break;
case PIN_GUARD_4_PIN_NR : paramValues[id] = PIN_GUARD_4_PIN_NR_DEFAULT; break;
case PIN_GUARD_4_TIME_OUT : paramValues[id] = PIN_GUARD_4_TIME_OUT_DEFAULT; break;
case PIN_GUARD_4_ACTIVE_STATE : paramValues[id] = PIN_GUARD_4_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_4_PIN_NR:
paramValues[id] = PIN_GUARD_4_PIN_NR_DEFAULT;
break;
case PIN_GUARD_4_TIME_OUT:
paramValues[id] = PIN_GUARD_4_TIME_OUT_DEFAULT;
break;
case PIN_GUARD_4_ACTIVE_STATE:
paramValues[id] = PIN_GUARD_4_ACTIVE_STATE_DEFAULT;
break;
case PIN_GUARD_5_PIN_NR : paramValues[id] = PIN_GUARD_5_PIN_NR_DEFAULT; break;
case PIN_GUARD_5_TIME_OUT : paramValues[id] = PIN_GUARD_5_TIME_OUT_DEFAULT; break;
case PIN_GUARD_5_ACTIVE_STATE : paramValues[id] = PIN_GUARD_5_ACTIVE_STATE_DEFAULT; break;
case PIN_GUARD_5_PIN_NR:
paramValues[id] = PIN_GUARD_5_PIN_NR_DEFAULT;
break;
case PIN_GUARD_5_TIME_OUT:
paramValues[id] = PIN_GUARD_5_TIME_OUT_DEFAULT;
break;
case PIN_GUARD_5_ACTIVE_STATE:
paramValues[id] = PIN_GUARD_5_ACTIVE_STATE_DEFAULT;
break;
default : paramValues[id] = 0; break;
default:
paramValues[id] = 0;
break;
}
}
bool ParameterList::validParam(int id) {
bool ParameterList::validParam(int id)
{
// Check if the id is a valid one
switch (id)
@ -353,4 +505,3 @@ bool ParameterList::validParam(int id) {
return false;
}
}

View File

@ -9,7 +9,6 @@
//#define NULL 0
const int PARAM_NR_OF_PARAMS = 225;
enum ParamListEnum
{
PARAM_VERSION = 0,
@ -80,7 +79,6 @@ enum ParamListEnum
MOVEMENT_AXIS_NR_STEPS_Y = 142,
MOVEMENT_AXIS_NR_STEPS_Z = 143,
// pin guard settings
PIN_GUARD_1_PIN_NR = 201,
PIN_GUARD_1_TIME_OUT = 202,
@ -108,8 +106,10 @@ enum ParamListEnum
#define NULL 0
*/
class ParameterList {
class ParameterList
{
ParamListEnum paramListEnum;
public:
static ParameterList *getInstance();
int writeValue(int id, int value);
@ -137,8 +137,6 @@ private:
void operator=(ParameterList const &);
int paramChangeNr;
};
#endif /* PARAMETERLIST_H_ */

View File

@ -3,48 +3,59 @@
static PinControl *instance;
PinControl * PinControl::getInstance() {
if (!instance) {
PinControl *PinControl::getInstance()
{
if (!instance)
{
instance = new PinControl();
};
return instance;
}
;
};
PinControl::PinControl() {
PinControl::PinControl()
{
}
int PinControl::setMode(int pinNr, int mode) {
int PinControl::setMode(int pinNr, int mode)
{
pinMode(pinNr, mode);
return 0;
}
int PinControl::writeValue(int pinNr, int value, int mode) {
if (mode == 0) {
int PinControl::writeValue(int pinNr, int value, int mode)
{
if (mode == 0)
{
digitalWrite(pinNr, value);
return 0;
}
if (mode == 1) {
if (mode == 1)
{
analogWrite(pinNr, value);
return 0;
}
return 1;
}
int PinControl::readValue(int pinNr, int mode) {
int PinControl::readValue(int pinNr, int mode)
{
int value = 0;
if (mode == 0) {
if (digitalRead(pinNr) == 1){
if (mode == 0)
{
if (digitalRead(pinNr) == 1)
{
value = 1;
}
}
if (mode == 1) {
if (mode == 1)
{
value = analogRead(pinNr);
}
if (mode == 0 || mode == 1) {
if (mode == 0 || mode == 1)
{
Serial.print("R41");
Serial.print(" ");
@ -58,12 +69,14 @@ int PinControl::readValue(int pinNr, int mode) {
return 0;
}
else {
else
{
return 1;
}
}
int PinControl::writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode) {
int PinControl::writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode)
{
writeValue(pinNr, valueOne, mode);
delay(time);
writeValue(pinNr, valueTwo, mode);

View File

@ -16,7 +16,8 @@
#include <stdlib.h>
#include "CurrentState.h"
class PinControl {
class PinControl
{
public:
static PinControl *getInstance();

View File

@ -3,15 +3,17 @@
static PinGuard *instance;
PinGuard * PinGuard::getInstance() {
if (!instance) {
PinGuard *PinGuard::getInstance()
{
if (!instance)
{
instance = new PinGuard();
};
return instance;
}
;
};
PinGuard::PinGuard() {
PinGuard::PinGuard()
{
pinGuardPin[0] = PinGuardPin();
pinGuardPin[1] = PinGuardPin();
@ -19,10 +21,10 @@ PinGuard::PinGuard() {
pinGuardPin[3] = PinGuardPin();
pinGuardPin[4] = PinGuardPin();
loadConfig();
}
void PinGuard::loadConfig() {
void PinGuard::loadConfig()
{
pinGuardPin[0].loadPinConfig(PIN_GUARD_1_PIN_NR, PIN_GUARD_1_ACTIVE_STATE, PIN_GUARD_1_TIME_OUT);
pinGuardPin[1].loadPinConfig(PIN_GUARD_2_PIN_NR, PIN_GUARD_2_ACTIVE_STATE, PIN_GUARD_2_TIME_OUT);
pinGuardPin[2].loadPinConfig(PIN_GUARD_3_PIN_NR, PIN_GUARD_3_ACTIVE_STATE, PIN_GUARD_3_TIME_OUT);
@ -30,7 +32,8 @@ void PinGuard::loadConfig() {
pinGuardPin[4].loadPinConfig(PIN_GUARD_5_PIN_NR, PIN_GUARD_5_ACTIVE_STATE, PIN_GUARD_5_TIME_OUT);
}
void PinGuard::checkPins() {
void PinGuard::checkPins()
{
pinGuardPin[0].processTick();
pinGuardPin[1].processTick();
pinGuardPin[2].processTick();

View File

@ -17,7 +17,8 @@
#include "PinGuardPin.h"
#include "ParameterList.h"
class PinGuard {
class PinGuard
{
public:
static PinGuard *getInstance();
@ -25,8 +26,6 @@ public:
void checkPins();
private:
//long pinTimeOut[100];
//long pinCurrentTime[100];
//void checkPin;

View File

@ -2,12 +2,14 @@
#include "PinGuardPin.h"
#include "ParameterList.h"
PinGuardPin::PinGuardPin() {
PinGuardPin::PinGuardPin()
{
pinNr = 0;
}
// Set the initial settings for what pin to check
void PinGuardPin::loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr) {
void PinGuardPin::loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr)
{
pinNr = ParameterList::getInstance()->getValue(pinNrParamNr);
activeState = (ParameterList::getInstance()->getValue(activeStateParamNr) == 1);
@ -17,23 +19,27 @@ void PinGuardPin::loadPinConfig(int pinNrParamNr, int activeStateParamNr, int ti
}
// Check each second if the time out is lapsed or the value has changed
void PinGuardPin::processTick() {
void PinGuardPin::processTick()
{
if (pinNr==0) {
if (pinNr == 0)
{
return;
}
currentStatePin = digitalRead(pinNr);
if (currentStatePin != activeState) {
if (currentStatePin != activeState)
{
timeOutCount = 0;
} else {
}
else
{
timeOutCount++;
}
if (timeOutCount >= timeOut) {
if (timeOutCount >= timeOut)
{
digitalWrite(pinNr, !activeState);
}
}

View File

@ -16,13 +16,14 @@
#include <stdlib.h>
//#include "ParameterList.h"
class PinGuardPin {
class PinGuardPin
{
public:
PinGuardPin();
void processTick();
void loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr);
private:
//PinControlPin(PinControlPin const&);
///void operator=(PinControlPin const&);
@ -32,7 +33,6 @@ private:
long timeOutCount;
bool activeState;
bool currentStatePin;
};
#endif /* PINGUARDPIN_H_ */

View File

@ -11,23 +11,27 @@ static ServoControl* instance;
Servo servos[2];
ServoControl * ServoControl::getInstance() {
if (!instance) {
ServoControl *ServoControl::getInstance()
{
if (!instance)
{
instance = new ServoControl();
};
return instance;
}
;
};
ServoControl::ServoControl() {
ServoControl::ServoControl()
{
}
int ServoControl::attach() {
int ServoControl::attach()
{
servos[0].attach(SERVO_0_PIN);
servos[1].attach(SERVO_1_PIN);
}
int ServoControl::setAngle(int pin, int angle) {
int ServoControl::setAngle(int pin, int angle)
{
/*
Serial.print("R99");
@ -45,7 +49,8 @@ int ServoControl::setAngle(int pin, int angle) {
Serial.print("\r\n");
*/
switch(pin) {
switch (pin)
{
case 4:
servos[0].write(angle);
break;
@ -58,6 +63,3 @@ int ServoControl::setAngle(int pin, int angle) {
return 0;
}

View File

@ -14,12 +14,14 @@
#include <stdio.h>
#include <stdlib.h>
class ServoControl {
class ServoControl
{
public:
static ServoControl *getInstance();
int attach();
int setAngle(int pin, int angle);
private:
ServoControl();
ServoControl(ServoControl const &);

View File

@ -3,30 +3,30 @@
static StatusList *instanceParam;
long statusValues[150];
StatusList * StatusList::getInstance() {
if (!instanceParam) {
StatusList *StatusList::getInstance()
{
if (!instanceParam)
{
instanceParam = new StatusList();
};
return instanceParam;
}
StatusList::StatusList() {
StatusList::StatusList()
{
statusValues[STATUS_GENERAL] = STATUS_GENERAL_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 StatusList::readValue(int id) {
int StatusList::readValue(int id)
{
long value = statusValues[id];
Serial.print("R31");
Serial.print(" ");
Serial.print("P");
@ -37,12 +37,11 @@ int StatusList::readValue(int id) {
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
return 0;
}
long StatusList::getValue(int id) {
long StatusList::getValue(int id)
{
/*
Serial.print("R99");
@ -58,10 +57,10 @@ long StatusList::getValue(int id) {
return statusValues[id];
}
int StatusList::setValue(int id, long value) {
int StatusList::setValue(int id, long value)
{
statusValues[id] = value;
return 0;
}

View File

@ -7,7 +7,6 @@
//#define NULL 0
enum StatusListEnum
{
STATUS_GENERAL = 0,
@ -22,19 +21,21 @@ enum StatusListEnum
#define NULL 0
*/
class StatusList {
class StatusList
{
StatusListEnum statusListEnum;
public:
static StatusList *getInstance();
int writeValue(int id, long value);
int readValue(int id);
long getValue(int id);
int setValue(int id, long value);
private:
StatusList();
StatusList(StatusList const &);
void operator=(StatusList const &);
};
#endif /* STATUSLIST_H_ */

View File

@ -2,15 +2,17 @@
static StepperControl *instance;
StepperControl * StepperControl::getInstance() {
if (!instance) {
StepperControl *StepperControl::getInstance()
{
if (!instance)
{
instance = new StepperControl();
};
return instance;
}
;
};
void StepperControl::reportStatus(StepperControlAxis* axis, int axisStatus) {
void StepperControl::reportStatus(StepperControlAxis *axis, int axisStatus)
{
Serial.print(COMM_REPORT_CMD_STATUS);
Serial.print(" ");
Serial.print(axis->label);
@ -19,7 +21,8 @@ void StepperControl::reportStatus(StepperControlAxis* axis, int axisStatus) {
CurrentState::getInstance()->printQAndNewLine();
}
void StepperControl::reportCalib(StepperControlAxis* axis, int calibStatus) {
void StepperControl::reportCalib(StepperControlAxis *axis, int calibStatus)
{
Serial.print(COMM_REPORT_CALIB_STATUS);
Serial.print(" ");
Serial.print(axis->label);
@ -28,40 +31,48 @@ void StepperControl::reportCalib(StepperControlAxis* axis, int calibStatus) {
CurrentState::getInstance()->printQAndNewLine();
}
void StepperControl::checkAxisSubStatus(StepperControlAxis* axis, int* axisSubStatus) {
void StepperControl::checkAxisSubStatus(StepperControlAxis *axis, int *axisSubStatus)
{
int newStatus = 0;
bool statusChanged = false;
if (axis->isAccelerating()) {
if (axis->isAccelerating())
{
newStatus = COMM_REPORT_MOVE_STATUS_ACCELERATING;
}
if (axis->isCruising()) {
if (axis->isCruising())
{
newStatus = COMM_REPORT_MOVE_STATUS_CRUISING;
}
if (axis->isDecelerating()) {
if (axis->isDecelerating())
{
newStatus = COMM_REPORT_MOVE_STATUS_DECELERATING;
}
if (axis->isCrawling()) {
if (axis->isCrawling())
{
newStatus = COMM_REPORT_MOVE_STATUS_CRAWLING;
}
// if the status changes, send out a status report
if (*axisSubStatus != newStatus && newStatus > 0) {
if (*axisSubStatus != newStatus && newStatus > 0)
{
statusChanged = true;
}
*axisSubStatus = newStatus;
if (statusChanged) {
if (statusChanged)
{
reportStatus(&axisX, *axisSubStatus);
}
}
//const int MOVEMENT_INTERRUPT_SPEED = 100; // Interrupt cycle in micro seconds
StepperControl::StepperControl() {
StepperControl::StepperControl()
{
// Initialize some variables for testing
@ -91,11 +102,11 @@ StepperControl::StepperControl() {
loadSettings();
motorMotorsEnabled = false;
}
void StepperControl::loadSettings() {
void StepperControl::loadSettings()
{
// Load motor settings
@ -120,10 +131,10 @@ void StepperControl::loadSettings() {
encoderX.loadSettings(motorConsEncoderType[0], motorConsEncoderScaling[0]);
encoderY.loadSettings(motorConsEncoderType[1], motorConsEncoderScaling[1]);
encoderZ.loadSettings(motorConsEncoderType[2], motorConsEncoderScaling[2]);
}
void StepperControl::test() {
void StepperControl::test()
{
Serial.print("R99");
Serial.print(" mot x = ");
@ -159,7 +170,8 @@ void StepperControl::test() {
//Serial.print("\r\n");
}
void StepperControl::test2() {
void StepperControl::test2()
{
CurrentState::getInstance()->printPosition();
encoderX.test();
//encoderY.test();
@ -175,8 +187,8 @@ void StepperControl::test2() {
*/
int StepperControl::moveToCoords(long xDest, long yDest, long zDest,
unsigned int xMaxSpd, unsigned int yMaxSpd, unsigned int zMaxSpd,
bool xHome, bool yHome, bool zHome
) {
bool xHome, bool yHome, bool zHome)
{
unsigned long currentMillis = 0;
unsigned long timeStart = millis();
@ -191,18 +203,20 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
// load current encoder coordinates
//axisX.setCurrentPosition(encoderX.currentPosition());
// if a speed is given in the command, use that instead of the config speed
if (xMaxSpd > 0 && xMaxSpd < speedMax[0]) {
if (xMaxSpd > 0 && xMaxSpd < speedMax[0])
{
speedMax[0] = xMaxSpd;
}
if (yMaxSpd > 0 && yMaxSpd < speedMax[1]) {
if (yMaxSpd > 0 && yMaxSpd < speedMax[1])
{
speedMax[1] = yMaxSpd;
}
if (zMaxSpd > 0 && zMaxSpd < speedMax[2]) {
if (zMaxSpd > 0 && zMaxSpd < speedMax[2])
{
speedMax[2] = zMaxSpd;
}
@ -277,7 +291,8 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
axisZ.checkMovement();
// Let the interrupt handle all the movements
while (axisActive[0] || axisActive[1] || axisActive[2]) {
while (axisActive[0] || axisActive[1] || axisActive[2])
{
checkAxisSubStatus(&axisX, &axisSubStep[0]);
checkAxisSubStatus(&axisY, &axisSubStep[1]);
@ -298,29 +313,32 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
//checkAxisVsEncoder(&axisY, &encoderY, &motorConsMissedSteps[1], &motorLastPosition[1], &motorConsMissedStepsDecay[1], &motorConsEncoderEnabled[1]);
//checkAxisVsEncoder(&axisZ, &encoderZ, &motorConsMissedSteps[2], &motorLastPosition[2], &motorConsMissedStepsDecay[2], &motorConsEncoderEnabled[2]);
if (motorConsMissedSteps[0] > motorConsMissedStepsMax[0]) {
if (motorConsMissedSteps[0] > motorConsMissedStepsMax[0])
{
axisX.deactivateAxis();
Serial.print("R99");
Serial.print(" deactivate motor X due to missed steps");
Serial.print("\r\n");
if (axisX.movingToHome()) {
if (axisX.movingToHome())
{
encoderX.setPosition(0);
axisX.setCurrentPosition(0);
Serial.print("R99");
Serial.print(" home position X axis detected with encoder");
Serial.print("\r\n");
}
}
if (motorConsMissedSteps[1] > motorConsMissedStepsMax[1]) {
if (motorConsMissedSteps[1] > motorConsMissedStepsMax[1])
{
axisY.deactivateAxis();
Serial.print("R99");
Serial.print(" deactivate motor Y due to missed steps");
Serial.print("\r\n");
if (axisY.movingToHome()) {
if (axisY.movingToHome())
{
encoderY.setPosition(0);
axisY.setCurrentPosition(0);
Serial.print("R99");
@ -329,13 +347,15 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
}
}
if (motorConsMissedSteps[2] > motorConsMissedStepsMax[2]) {
if (motorConsMissedSteps[2] > motorConsMissedStepsMax[2])
{
axisZ.deactivateAxis();
Serial.print("R99");
Serial.print(" deactivate motor Z due to missed steps");
Serial.print("\r\n");
if (axisZ.movingToHome()) {
if (axisZ.movingToHome())
{
encoderZ.setPosition(0);
axisZ.setCurrentPosition(0);
Serial.print("R99");
@ -344,22 +364,24 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
}
}
if (axisX.endStopAxisReached(false)) {
if (axisX.endStopAxisReached(false))
{
axisX.setCurrentPosition(0);
encoderX.setPosition(0);
}
if (axisY.endStopAxisReached(false)) {
if (axisY.endStopAxisReached(false))
{
axisY.setCurrentPosition(0);
encoderY.setPosition(0);
}
if (axisZ.endStopAxisReached(false)) {
if (axisZ.endStopAxisReached(false))
{
axisZ.setCurrentPosition(0);
encoderZ.setPosition(0);
}
axisActive[0] = axisX.isAxisActive();
axisActive[1] = axisY.isAxisActive();
axisActive[2] = axisZ.isAxisActive();
@ -375,23 +397,28 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
storeEndStops();
// Check timeouts
if (axisActive[0] == true && ((millis() >= timeStart && millis() - timeStart > timeOut[0] * 1000) || (millis() < timeStart && millis() > timeOut[0] * 1000))) {
if (axisActive[0] == true && ((millis() >= timeStart && millis() - timeStart > timeOut[0] * 1000) || (millis() < timeStart && millis() > timeOut[0] * 1000)))
{
Serial.print("R99 timeout X axis\r\n");
error = 1;
}
if (axisActive[1] == true && ((millis() >= timeStart && millis() - timeStart > timeOut[0] * 1000) || (millis() < timeStart && millis() > timeOut[0] * 1000))) {
if (axisActive[1] == true && ((millis() >= timeStart && millis() - timeStart > timeOut[0] * 1000) || (millis() < timeStart && millis() > timeOut[0] * 1000)))
{
Serial.print("R99 timeout Y axis\r\n");
error = 1;
}
if (axisActive[2] == true && ((millis() >= timeStart && millis() - timeStart > timeOut[0] * 1000) || (millis() < timeStart && millis() > timeOut[0] * 1000))) {
if (axisActive[2] == true && ((millis() >= timeStart && millis() - timeStart > timeOut[0] * 1000) || (millis() < timeStart && millis() > timeOut[0] * 1000)))
{
Serial.print("R99 timeout Z axis\r\n");
error = 1;
}
// Check if there is an emergency stop command
if (Serial.available() > 0) {
if (Serial.available() > 0)
{
incomingByte = Serial.read();
if (incomingByte == 69 || incomingByte == 101) {
if (incomingByte == 69 || incomingByte == 101)
{
Serial.print("R99 emergency stop\r\n");
axisX.deactivateAxis();
axisY.deactivateAxis();
@ -400,7 +427,8 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
}
}
if (error == 1) {
if (error == 1)
{
Serial.print("R99 error\r\n");
axisActive[0] = false;
@ -445,9 +473,7 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
//Serial.print(" axis pos ");
//Serial.print(axisX.currentPosition());
//Serial.print("\r\n");
}
}
Serial.print("R99 stopped\r\n");
@ -499,7 +525,8 @@ int StepperControl::moveToCoords( long xDest, long yDest, long zDest,
// Calibration
//
int StepperControl::calibrateAxis(int axis) {
int StepperControl::calibrateAxis(int axis)
{
// Load motor and encoder settings
@ -515,7 +542,6 @@ int StepperControl::calibrateAxis(int axis) {
int incomingByte = 0;
int error = 0;
bool invertEndStops = false;
int parEndInv;
int parNbrStp;
@ -536,7 +562,8 @@ int StepperControl::calibrateAxis(int axis) {
StepperControlAxis *calibAxis;
StepperControlEncoder *calibEncoder;
switch (axis) {
switch (axis)
{
case 0:
calibAxis = &axisX;
calibEncoder = &encoderX;
@ -553,7 +580,8 @@ int StepperControl::calibrateAxis(int axis) {
case 1:
calibAxis = &axisY;
calibEncoder = &encoderY;
parEndInv = MOVEMENT_INVERT_ENDPOINTS_Y;;
parEndInv = MOVEMENT_INVERT_ENDPOINTS_Y;
;
parNbrStp = MOVEMENT_AXIS_NR_STEPS_Y;
invertEndStops = endStInv[1];
missedSteps = &motorConsMissedSteps[1];
@ -581,10 +609,10 @@ int StepperControl::calibrateAxis(int axis) {
return 1;
}
// Preliminary checks
if (calibAxis->endStopMin() || calibAxis->endStopMax()) {
if (calibAxis->endStopMin() || calibAxis->endStopMax())
{
Serial.print("R99 Calibration error: end stop active before start\r\n");
return 1;
}
@ -616,14 +644,17 @@ int StepperControl::calibrateAxis(int axis) {
reportCalib(&axisX, COMM_REPORT_CALIBRATE_STATUS_TO_HOME);
while (!movementDone && error == 0) {
while (!movementDone && error == 0)
{
//checkAxisVsEncoder(&axisX, &encoderX, &motorConsMissedSteps[0], &motorLastPosition[0], &motorConsMissedStepsDecay[0], &motorConsEncoderEnabled[0]);
// Check if there is an emergency stop command
if (Serial.available() > 0) {
if (Serial.available() > 0)
{
incomingByte = Serial.read();
if (incomingByte == 69 || incomingByte == 101) {
if (incomingByte == 69 || incomingByte == 101)
{
Serial.print("R99 emergency stop\r\n");
movementDone = true;
error = 1;
@ -636,7 +667,8 @@ int StepperControl::calibrateAxis(int axis) {
//}
// Move until the end stop for home position is reached, either by end stop or motot skipping
if ((!calibAxis->endStopMin() && !calibAxis->endStopMax()) && !movementDone && (*missedSteps < *missedStepsMax)) {
if ((!calibAxis->endStopMin() && !calibAxis->endStopMax()) && !movementDone && (*missedSteps < *missedStepsMax))
{
calibAxis->setStepAxis();
@ -669,8 +701,9 @@ int StepperControl::calibrateAxis(int axis) {
calibAxis->resetMotorStep();
delayMicroseconds(100000 / speedMin[axis] / 2);
} else {
}
else
{
movementDone = true;
Serial.print("R99 movement done\r\n");
@ -692,10 +725,14 @@ int StepperControl::calibrateAxis(int axis) {
// Report back the end stop setting
if (error == 0) {
if (invertEndStops) {
if (error == 0)
{
if (invertEndStops)
{
paramValueInt = 1;
} else {
}
else
{
paramValueInt = 0;
}
@ -735,12 +772,15 @@ int StepperControl::calibrateAxis(int axis) {
long encoderStartPoint = calibEncoder->currentPosition();
long encoderEndPoint = calibEncoder->currentPosition();
while (!movementDone && error == 0) {
while (!movementDone && error == 0)
{
// Check if there is an emergency stop command
if (Serial.available() > 0) {
if (Serial.available() > 0)
{
incomingByte = Serial.read();
if (incomingByte == 69 || incomingByte == 101) {
if (incomingByte == 69 || incomingByte == 101)
{
Serial.print("R99 emergency stop\r\n");
movementDone = true;
error = 1;
@ -748,19 +788,20 @@ int StepperControl::calibrateAxis(int axis) {
}
// Ignore the missed steps at startup time
if (stepsCount < 10) {
if (stepsCount < 10)
{
*missedSteps = 0;
}
// Move until the end stop at the other side of the axis is reached
if (((!invertEndStops && !calibAxis->endStopMax()) || (invertEndStops && !calibAxis->endStopMin())) && !movementDone && (*missedSteps < *missedStepsMax)) {
if (((!invertEndStops && !calibAxis->endStopMax()) || (invertEndStops && !calibAxis->endStopMin())) && !movementDone && (*missedSteps < *missedStepsMax))
{
calibAxis->setStepAxis();
stepsCount++;
//checkAxisVsEncoder(&axisX, &encoderX, &motorConsMissedSteps[0], &motorLastPosition[0], &motorConsMissedStepsDecay[0], &motorConsEncoderEnabled[0]);
delayMicroseconds(100000 / speedMin[axis] / 2);
if (stepsCount % (speedMin[axis] * 3) == 0)
@ -773,14 +814,14 @@ int StepperControl::calibrateAxis(int axis) {
calibAxis->resetMotorStep();
delayMicroseconds(100000 / speedMin[axis] / 2);
} else {
}
else
{
Serial.print("R99 movement done\r\n");
movementDone = true;
}
}
Serial.print("R99");
Serial.print(" axis ");
Serial.print(calibAxis->label);
@ -791,13 +832,15 @@ int StepperControl::calibrateAxis(int axis) {
// if the encoder is enabled, use the encoder data instead of the step count
if (encoderEnabled) {
if (encoderEnabled)
{
stepsCount = abs(encoderEndPoint - encoderStartPoint);
}
// Report back the end stop setting
if (error == 0) {
if (error == 0)
{
Serial.print("R23");
Serial.print(" ");
Serial.print("P");
@ -816,8 +859,8 @@ int StepperControl::calibrateAxis(int axis) {
storeEndStops();
reportEndStops();
switch (axis) {
switch (axis)
{
case 0:
CurrentState::getInstance()->setX(stepsCount);
break;
@ -831,7 +874,6 @@ int StepperControl::calibrateAxis(int axis) {
reportPosition();
*axisStatus = COMM_REPORT_MOVE_STATUS_IDLE;
reportStatus(&axisX, axisSubStep[0]);
@ -840,9 +882,9 @@ int StepperControl::calibrateAxis(int axis) {
return error;
}
// Handle movement by checking each axis
void StepperControl::handleMovementInterrupt(void){
void StepperControl::handleMovementInterrupt(void)
{
encoderX.readEncoder();
encoderY.readEncoder();
@ -855,17 +897,18 @@ void StepperControl::handleMovementInterrupt(void){
checkAxisVsEncoder(&axisX, &encoderX, &motorConsMissedSteps[0], &motorLastPosition[0], &motorConsMissedStepsDecay[0], &motorConsEncoderEnabled[0]);
checkAxisVsEncoder(&axisY, &encoderY, &motorConsMissedSteps[1], &motorLastPosition[1], &motorConsMissedStepsDecay[1], &motorConsEncoderEnabled[1]);
checkAxisVsEncoder(&axisZ, &encoderZ, &motorConsMissedSteps[2], &motorLastPosition[2], &motorConsMissedStepsDecay[2], &motorConsEncoderEnabled[2]);
}
int debugPrintCount = 0;
// Check encoder to verify the motor is at the right position
void StepperControl::checkAxisVsEncoder(StepperControlAxis* axis, StepperControlEncoder* encoder, float* missedSteps, long* lastPosition, float* encoderStepDecay, bool* encoderEnabled) {
void StepperControl::checkAxisVsEncoder(StepperControlAxis *axis, StepperControlEncoder *encoder, float *missedSteps, long *lastPosition, float *encoderStepDecay, bool *encoderEnabled)
{
// If a step is done
//if (axis->isStepDone() && axis->currentPosition() % 3 == 0) {
if (*encoderEnabled && axis->isStepDone()) {
if (*encoderEnabled && axis->isStepDone())
{
bool stepMissed = false;
@ -899,21 +942,25 @@ void StepperControl::checkAxisVsEncoder(StepperControlAxis* axis, StepperControl
*/
// Decrease amount of missed steps if there are no missed step
if (*missedSteps > 0) {
if (*missedSteps > 0)
{
(*missedSteps) -= (*encoderStepDecay);
}
// Check if the encoder goes in the wrong direction or nothing moved
if ((axis->movingUp() && *lastPosition >= axis->currentPosition()) ||
(!axis->movingUp() && *lastPosition <= axis->currentPosition())) {
(!axis->movingUp() && *lastPosition <= axis->currentPosition()))
{
stepMissed = true;
}
if (abs(axis->currentPosition() - encoder->currentPosition()) > 2) {
if (abs(axis->currentPosition() - encoder->currentPosition()) > 2)
{
stepMissed = true;
}
if (stepMissed) {
if (stepMissed)
{
axis->setCurrentPosition(encoder->currentPosition());
(*missedSteps)++;
}
@ -923,7 +970,8 @@ void StepperControl::checkAxisVsEncoder(StepperControlAxis* axis, StepperControl
}
}
void StepperControl::loadMotorSettings() {
void StepperControl::loadMotorSettings()
{
// Load settings
@ -970,17 +1018,19 @@ void StepperControl::loadMotorSettings() {
axisX.loadMotorSettings(speedMax[0], speedMin[0], stepsAcc[0], timeOut[0], homeIsUp[0], motorInv[0], endStInv[0], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[0], motor2Inv[0], endStEnbl[0]);
axisY.loadMotorSettings(speedMax[1], speedMin[1], stepsAcc[1], timeOut[1], homeIsUp[1], motorInv[1], endStInv[1], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[1], motor2Inv[1], endStEnbl[1]);
axisZ.loadMotorSettings(speedMax[2], speedMin[2], stepsAcc[2], timeOut[2], homeIsUp[2], motorInv[2], endStInv[2], MOVEMENT_INTERRUPT_SPEED, motor2Enbl[2], motor2Inv[2], endStEnbl[2]);
}
bool StepperControl::intToBool(int value) {
if (value == 1) {
bool StepperControl::intToBool(int value)
{
if (value == 1)
{
return true;
}
return false;
}
void StepperControl::loadEncoderSettings() {
void StepperControl::loadEncoderSettings()
{
// Load encoder settings
@ -1008,37 +1058,49 @@ void StepperControl::loadEncoderSettings() {
motorConsEncoderScaling[1] = ParameterList::getInstance()->getValue(ENCODER_SCALING_Y);
motorConsEncoderScaling[2] = ParameterList::getInstance()->getValue(ENCODER_SCALING_Z);
if (ParameterList::getInstance()->getValue(ENCODER_ENABLED_X) == 1) {
if (ParameterList::getInstance()->getValue(ENCODER_ENABLED_X) == 1)
{
motorConsEncoderEnabled[0] = true;
} else {
}
else
{
motorConsEncoderEnabled[0] = false;
}
if (ParameterList::getInstance()->getValue(ENCODER_ENABLED_Y) == 1) {
if (ParameterList::getInstance()->getValue(ENCODER_ENABLED_Y) == 1)
{
motorConsEncoderEnabled[1] = true;
} else {
}
else
{
motorConsEncoderEnabled[1] = false;
}
if (ParameterList::getInstance()->getValue(ENCODER_ENABLED_Z) == 1) {
if (ParameterList::getInstance()->getValue(ENCODER_ENABLED_Z) == 1)
{
motorConsEncoderEnabled[2] = true;
} else {
}
else
{
motorConsEncoderEnabled[2] = false;
}
}
unsigned long StepperControl::getMaxLength(unsigned long lengths[3]) {
unsigned long StepperControl::getMaxLength(unsigned long lengths[3])
{
unsigned long max = lengths[0];
for (int i = 1; i < 3; i++) {
if (lengths[i] > max) {
for (int i = 1; i < 3; i++)
{
if (lengths[i] > max)
{
max = lengths[i];
}
}
return max;
}
void StepperControl::enableMotors() {
void StepperControl::enableMotors()
{
motorMotorsEnabled = true;
axisX.enableMotor();
@ -1047,7 +1109,8 @@ void StepperControl::enableMotors() {
delay(100);
}
void StepperControl::disableMotors() {
void StepperControl::disableMotors()
{
motorMotorsEnabled = false;
axisX.disableMotor();
@ -1056,66 +1119,83 @@ void StepperControl::disableMotors() {
delay(100);
}
bool StepperControl::motorsEnabled() {
bool StepperControl::motorsEnabled()
{
return motorMotorsEnabled;
}
bool StepperControl::endStopsReached() {
bool StepperControl::endStopsReached()
{
if (axisX.endStopsReached() ||
axisY.endStopsReached() ||
axisZ.endStopsReached()) {
axisZ.endStopsReached())
{
return true;
}
return false;
}
void StepperControl::storePosition(){
void StepperControl::storePosition()
{
if (motorConsEncoderEnabled[0]) {
if (motorConsEncoderEnabled[0])
{
CurrentState::getInstance()->setX(encoderX.currentPosition());
} else {
}
else
{
CurrentState::getInstance()->setX(axisX.currentPosition());
}
if (motorConsEncoderEnabled[1]) {
if (motorConsEncoderEnabled[1])
{
CurrentState::getInstance()->setY(encoderY.currentPosition());
} else {
}
else
{
CurrentState::getInstance()->setY(axisY.currentPosition());
}
if (motorConsEncoderEnabled[2]) {
if (motorConsEncoderEnabled[2])
{
CurrentState::getInstance()->setZ(encoderZ.currentPosition());
} else {
}
else
{
CurrentState::getInstance()->setZ(axisZ.currentPosition());
}
}
void StepperControl::reportEndStops() {
void StepperControl::reportEndStops()
{
CurrentState::getInstance()->printEndStops();
}
void StepperControl::reportPosition(){
void StepperControl::reportPosition()
{
CurrentState::getInstance()->printPosition();
}
void StepperControl::storeEndStops() {
void StepperControl::storeEndStops()
{
CurrentState::getInstance()->storeEndStops();
}
void StepperControl::setPositionX(long pos) {
void StepperControl::setPositionX(long pos)
{
axisX.setCurrentPosition(pos);
encoderX.setPosition(pos);
}
void StepperControl::setPositionY(long pos) {
void StepperControl::setPositionY(long pos)
{
axisY.setCurrentPosition(pos);
encoderY.setPosition(pos);
}
void StepperControl::setPositionZ(long pos) {
void StepperControl::setPositionZ(long pos)
{
axisZ.setCurrentPosition(pos);
encoderZ.setPosition(pos);
}

View File

@ -19,7 +19,8 @@
#include <stdlib.h>
#include "Command.h"
class StepperControl {
class StepperControl
{
public:
StepperControl();
StepperControl(StepperControl const &);
@ -31,8 +32,7 @@ public:
// unsigned int maxAccelerationStepsPerSecond);
int moveToCoords(long xDest, long yDest, long zDest,
unsigned int xMaxSpd, unsigned int yMaxSpd, unsigned int zMaxSpd,
bool homeX, bool homeY, bool homeZ
);
bool homeX, bool homeY, bool homeZ);
void handleMovementInterrupt();
int calibrateAxis(int axis);

View File

@ -1,6 +1,7 @@
#include "StepperControlAxis.h"
StepperControlAxis::StepperControlAxis() {
StepperControlAxis::StepperControlAxis()
{
lastCalcLog = 0;
pinStep = 0;
@ -31,7 +32,8 @@ StepperControlAxis::StepperControlAxis() {
movementMoving = false;
}
void StepperControlAxis::test() {
void StepperControlAxis::test()
{
Serial.print("R99");
Serial.print(" cur loc = ");
Serial.print(coordCurrentPoint);
@ -43,7 +45,8 @@ void StepperControlAxis::test() {
Serial.print("\r\n");
}
unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec) {
unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec)
{
int newSpeed = 0;
@ -52,50 +55,66 @@ unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long curren
long staPos;
long endPos;
movementAccelerating = false;
movementDecelerating = false;
movementCruising = false;
movementCrawling = false;
movementMoving = false;
if (abs(sourcePosition) < abs(destinationPosition)) {
if (abs(sourcePosition) < abs(destinationPosition))
{
staPos = abs(sourcePosition);
endPos = abs(destinationPosition);;
} else {
staPos = abs(destinationPosition);;
endPos = abs(destinationPosition);
;
}
else
{
staPos = abs(destinationPosition);
;
endPos = abs(sourcePosition);
}
unsigned long halfway = ((endPos - staPos) / 2) + staPos;
// Set the minimum speed if the position would be out of bounds
if (curPos < staPos || curPos > endPos) {
if (curPos < staPos || curPos > endPos)
{
newSpeed = minSpeed;
movementCrawling = true;
movementMoving = true;
} else {
if (curPos >= staPos && curPos <= halfway) {
}
else
{
if (curPos >= staPos && curPos <= halfway)
{
// accelerating
if (curPos > (staPos + stepsAccDec)) {
if (curPos > (staPos + stepsAccDec))
{
// now beyond the accelleration point to go full speed
newSpeed = maxSpeed + 1;
movementCruising = true;
movementMoving = true;
} else {
}
else
{
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (curPos - staPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementAccelerating = true;
movementMoving = true;
}
} else {
}
else
{
// decelerating
if (curPos < (endPos - stepsAccDec)) {
if (curPos < (endPos - stepsAccDec))
{
// still before the deceleration point so keep going at full speed
newSpeed = maxSpeed + 2;
movementCruising = true;
movementMoving = true;
} else {
}
else
{
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (endPos - curPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementDecelerating = true;
@ -104,8 +123,8 @@ unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long curren
}
}
if (debugPrint && (millis() - lastCalcLog > 1000)) {
if (debugPrint && (millis() - lastCalcLog > 1000))
{
lastCalcLog = millis();
@ -133,39 +152,48 @@ unsigned int StepperControlAxis::calculateSpeed(long sourcePosition, long curren
Serial.print("\r\n");
}
// Return the calculated speed, in steps per second
return newSpeed;
}
void StepperControlAxis::checkAxisDirection() {
void StepperControlAxis::checkAxisDirection()
{
if (coordHomeAxis){
if (coordHomeAxis)
{
// When home is active, the direction is fixed
movementUp = motorHomeIsUp;
movementToHome = true;
} else {
}
else
{
// For normal movement, move in direction of destination
movementUp = (coordCurrentPoint < coordDestinationPoint);
movementToHome = (abs(coordCurrentPoint) >= abs(coordDestinationPoint));
}
if (coordCurrentPoint == 0) {
if (coordCurrentPoint == 0)
{
// Go slow when theoretical end point reached but there is no end stop siganl
axisSpeed = motorSpeedMin;
}
}
void StepperControlAxis::setDirectionAxis() {
void StepperControlAxis::setDirectionAxis()
{
if (((!coordHomeAxis && coordCurrentPoint < coordDestinationPoint) || (coordHomeAxis && motorHomeIsUp)) ^ motorMotorInv) {
if (((!coordHomeAxis && coordCurrentPoint < coordDestinationPoint) || (coordHomeAxis && motorHomeIsUp)) ^ motorMotorInv)
{
setDirectionUp();
} else {
}
else
{
setDirectionDown();
}
}
void StepperControlAxis::checkMovement() {
void StepperControlAxis::checkMovement()
{
checkAxisDirection();
@ -174,15 +202,15 @@ void StepperControlAxis::checkMovement() {
(
(coordDestinationPoint > coordSourcePoint && coordCurrentPoint < coordDestinationPoint) ||
(coordDestinationPoint < coordSourcePoint && coordCurrentPoint > coordDestinationPoint) ||
coordHomeAxis
)
&& axisActive
) {
coordHomeAxis) &&
axisActive)
{
// home or destination not reached, keep moving
// If end stop reached or the encoder doesn't move anymore, stop moving motor, otherwise set the timing for the next step
if ((coordHomeAxis && !endStopAxisReached(false)) || (!coordHomeAxis && !endStopAxisReached(!movementToHome))) {
if ((coordHomeAxis && !endStopAxisReached(false)) || (!coordHomeAxis && !endStopAxisReached(!movementToHome)))
{
// Get the axis speed, in steps per second
axisSpeed = calculateSpeed(coordSourcePoint, coordCurrentPoint, coordDestinationPoint,
@ -198,38 +226,46 @@ void StepperControlAxis::checkMovement() {
stepOffTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed);
}
}
else {
else
{
axisActive = false;
}
} else {
}
else
{
// Destination or home reached. Deactivate the axis.
axisActive = false;
}
// If end stop for home is active, set the position to zero
if (endStopAxisReached(false)) {
if (endStopAxisReached(false))
{
coordCurrentPoint = 0;
}
}
void StepperControlAxis::checkTiming() {
void StepperControlAxis::checkTiming()
{
//int i;
if (axisActive) {
if (axisActive)
{
moveTicks++;
if (moveTicks >= stepOffTick) {
if (moveTicks >= stepOffTick)
{
// Negative flank for the steps
resetMotorStep();
checkMovement();
}
else {
else
{
if (moveTicks == stepOnTick) {
if (moveTicks == stepOnTick)
{
// Positive flank for the steps
setStepAxis();
@ -238,11 +274,15 @@ void StepperControlAxis::checkTiming() {
}
}
void StepperControlAxis::setStepAxis() {
void StepperControlAxis::setStepAxis()
{
if (movementUp) {
if (movementUp)
{
coordCurrentPoint++;
} else {
}
else
{
coordCurrentPoint--;
}
@ -250,22 +290,27 @@ void StepperControlAxis::setStepAxis() {
setMotorStep();
}
bool StepperControlAxis::endStopAxisReached(bool movement_forward) {
bool StepperControlAxis::endStopAxisReached(bool movement_forward)
{
bool min_endstop = false;
bool max_endstop = false;
bool invert = false;
if (motorEndStopInv) {
if (motorEndStopInv)
{
invert = true;
}
// for the axis to check, retrieve the end stop status
if (!invert) {
if (!invert)
{
min_endstop = endStopMin();
max_endstop = endStopMax();
} else {
}
else
{
min_endstop = endStopMax();
max_endstop = endStopMin();
}
@ -273,14 +318,16 @@ bool StepperControlAxis::endStopAxisReached(bool movement_forward) {
// if moving forward, only check the end stop max
// for moving backwards, check only the end stop min
if((!movement_forward && min_endstop) || (movement_forward && max_endstop)) {
if ((!movement_forward && min_endstop) || (movement_forward && max_endstop))
{
return 1;
}
return 0;
}
void StepperControlAxis::StepperControlAxis::loadPinNumbers(int step, int dir, int enable, int min, int max,int step2, int dir2, int enable2) {
void StepperControlAxis::StepperControlAxis::loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2)
{
pinStep = step;
pinDirection = dir;
pinEnable = enable;
@ -293,10 +340,10 @@ void StepperControlAxis::StepperControlAxis::loadPinNumbers(int step, int dir, i
pinMax = max;
}
void StepperControlAxis::loadMotorSettings(
long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv,
bool endStInv, long interruptSpeed, bool motor2Enbl,bool motor2Inv, bool endStEnbl) {
bool endStInv, long interruptSpeed, bool motor2Enbl, bool motor2Inv, bool endStEnbl)
{
motorSpeedMax = speedMax;
motorSpeedMin = speedMin;
@ -311,7 +358,8 @@ void StepperControlAxis::loadMotorSettings(
motorMotor2Inv = motor2Inv;
}
void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint, bool home) {
void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint, bool home)
{
coordSourcePoint = sourcePoint;
coordCurrentPoint = sourcePoint;
@ -319,11 +367,13 @@ void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint
coordHomeAxis = home;
// Limit normal movmement to the home position
if (!motorHomeIsUp && coordDestinationPoint < 0) {
if (!motorHomeIsUp && coordDestinationPoint < 0)
{
coordDestinationPoint = 0;
}
if ( motorHomeIsUp && coordDestinationPoint > 0) {
if (motorHomeIsUp && coordDestinationPoint > 0)
{
coordDestinationPoint = 0;
}
@ -332,176 +382,230 @@ void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint
axisActive = true;
}
void StepperControlAxis::enableMotor() {
void StepperControlAxis::enableMotor()
{
digitalWrite(pinEnable, LOW);
if (motorMotor2Enl) {
if (motorMotor2Enl)
{
digitalWrite(pin2Enable, LOW);
}
movementMotorActive = true;
}
void StepperControlAxis::disableMotor() {
void StepperControlAxis::disableMotor()
{
digitalWrite(pinEnable, HIGH);
if (motorMotor2Enl) {
if (motorMotor2Enl)
{
digitalWrite(pin2Enable, HIGH);
}
movementMotorActive = false;
}
void StepperControlAxis::setDirectionUp() {
if (motorMotorInv) {
void StepperControlAxis::setDirectionUp()
{
if (motorMotorInv)
{
digitalWrite(pinDirection, LOW);
} else {
}
else
{
digitalWrite(pinDirection, HIGH);
}
if (motorMotor2Enl && motorMotor2Inv) {
if (motorMotor2Enl && motorMotor2Inv)
{
digitalWrite(pin2Direction, LOW);
} else {
}
else
{
digitalWrite(pin2Direction, HIGH);
}
}
void StepperControlAxis::setDirectionDown() {
if (motorMotorInv) {
void StepperControlAxis::setDirectionDown()
{
if (motorMotorInv)
{
digitalWrite(pinDirection, HIGH);
} else {
}
else
{
digitalWrite(pinDirection, LOW);
}
if (motorMotor2Enl && motorMotor2Inv) {
if (motorMotor2Enl && motorMotor2Inv)
{
digitalWrite(pin2Direction, HIGH);
} else {
}
else
{
digitalWrite(pin2Direction, LOW);
}
}
void StepperControlAxis::setMovementUp() {
void StepperControlAxis::setMovementUp()
{
movementUp = true;
}
void StepperControlAxis::setMovementDown() {
void StepperControlAxis::setMovementDown()
{
movementUp = false;
}
void StepperControlAxis::setDirectionHome() {
if (motorHomeIsUp) {
void StepperControlAxis::setDirectionHome()
{
if (motorHomeIsUp)
{
setDirectionUp();
setMovementUp();
} else {
}
else
{
setDirectionDown();
setMovementDown();
}
}
void StepperControlAxis::setDirectionAway() {
if (motorHomeIsUp) {
void StepperControlAxis::setDirectionAway()
{
if (motorHomeIsUp)
{
setDirectionDown();
setMovementDown();
} else {
}
else
{
setDirectionUp();
setMovementUp();
}
}
unsigned long StepperControlAxis::getLength(long l1, long l2) {
if (l1 > l2) {
unsigned long StepperControlAxis::getLength(long l1, long l2)
{
if (l1 > l2)
{
return l1 - l2;
} else {
}
else
{
return l2 - l1;
}
}
bool StepperControlAxis::endStopsReached() {
bool StepperControlAxis::endStopsReached()
{
return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv)) && motorEndStopEnbl;
}
bool StepperControlAxis::endStopMin() {
bool StepperControlAxis::endStopMin()
{
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMin) && motorEndStopEnbl;
}
bool StepperControlAxis::endStopMax() {
bool StepperControlAxis::endStopMax()
{
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMax) && motorEndStopEnbl;
}
bool StepperControlAxis::isAxisActive() {
bool StepperControlAxis::isAxisActive()
{
return axisActive;
}
void StepperControlAxis::deactivateAxis() {
void StepperControlAxis::deactivateAxis()
{
axisActive = false;
}
void StepperControlAxis::setMotorStep() {
void StepperControlAxis::setMotorStep()
{
digitalWrite(pinStep, HIGH);
if (pin2Enable) {
if (pin2Enable)
{
digitalWrite(pin2Step, HIGH);
}
}
void StepperControlAxis::resetMotorStep() {
void StepperControlAxis::resetMotorStep()
{
movementStepDone = true;
digitalWrite(pinStep, LOW);
if (pin2Enable) {
if (pin2Enable)
{
digitalWrite(pin2Step, LOW);
}
}
bool StepperControlAxis::pointReached(long currentPoint, long destinationPoint) {
bool StepperControlAxis::pointReached(long currentPoint, long destinationPoint)
{
return (destinationPoint == currentPoint);
}
long StepperControlAxis::currentPosition() {
long StepperControlAxis::currentPosition()
{
return coordCurrentPoint;
}
void StepperControlAxis::setCurrentPosition(long newPos) {
void StepperControlAxis::setCurrentPosition(long newPos)
{
coordCurrentPoint = newPos;
}
void StepperControlAxis::setMaxSpeed(long speed) {
void StepperControlAxis::setMaxSpeed(long speed)
{
motorSpeedMax = speed;
}
void StepperControlAxis::activateDebugPrint() {
void StepperControlAxis::activateDebugPrint()
{
debugPrint = true;
}
bool StepperControlAxis::isStepDone() {
bool StepperControlAxis::isStepDone()
{
return movementStepDone;
}
void StepperControlAxis::resetStepDone() {
void StepperControlAxis::resetStepDone()
{
movementStepDone = false;
}
bool StepperControlAxis::movingToHome() {
bool StepperControlAxis::movingToHome()
{
return movementToHome;
}
bool StepperControlAxis::movingUp() {
bool StepperControlAxis::movingUp()
{
return movementUp;
}
bool StepperControlAxis::isAccelerating() {
bool StepperControlAxis::isAccelerating()
{
return movementAccelerating;
}
bool StepperControlAxis::isDecelerating() {
bool StepperControlAxis::isDecelerating()
{
return movementDecelerating;
}
bool StepperControlAxis::isCruising() {
bool StepperControlAxis::isCruising()
{
return movementCruising;
}
bool StepperControlAxis::isCrawling() {
bool StepperControlAxis::isCrawling()
{
return movementCrawling;
}
bool StepperControlAxis::isMotorActive() {
bool StepperControlAxis::isMotorActive()
{
return movementMotorActive;
}

View File

@ -17,10 +17,10 @@
#include <stdio.h>
#include <stdlib.h>
class StepperControlAxis {
class StepperControlAxis
{
public:
StepperControlAxis();
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);
@ -76,7 +76,6 @@ public:
bool movementStarted;
private:
int lastCalcLog = 0;
bool debugPrint = false;
@ -139,8 +138,6 @@ private:
unsigned int calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec);
unsigned long getLength(long l1, long l2);
void checkAxisDirection();
};
#endif /* STEPPERCONTROLAXIS_H_ */

View File

@ -1,6 +1,7 @@
#include "StepperControlEncoder.h"
StepperControlEncoder::StepperControlEncoder() {
StepperControlEncoder::StepperControlEncoder()
{
//lastCalcLog = 0;
pinChannelA = 0;
@ -21,7 +22,8 @@ StepperControlEncoder::StepperControlEncoder() {
readChannelBQ = false;
}
void StepperControlEncoder::test() {
void StepperControlEncoder::test()
{
/*
Serial.print("R88 ");
Serial.print("position ");
@ -38,7 +40,8 @@ void StepperControlEncoder::test() {
*/
}
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ) {
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ)
{
pinChannelA = channelA;
pinChannelB = channelB;
pinChannelAQ = channelAQ;
@ -48,22 +51,28 @@ void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int chann
shiftChannels();
}
void StepperControlEncoder::loadSettings(int encType, int scaling) {
void StepperControlEncoder::loadSettings(int encType, int scaling)
{
encoderType = encType;
scalingFactor = scaling;
}
void StepperControlEncoder::setPosition(long newPosition) {
void StepperControlEncoder::setPosition(long newPosition)
{
position = newPosition;
}
long StepperControlEncoder::currentPosition() {
long StepperControlEncoder::currentPosition()
{
// Apply scaling to the output of the encoder, except when scaling is zero or lower
if (scalingFactor == 100 || scalingFactor <= 0) {
if (scalingFactor == 100 || scalingFactor <= 0)
{
return position;
} else {
}
else
{
return position * scalingFactor / 100;
}
}
@ -83,8 +92,8 @@ rotation ----------------------------------------------------->
*/
void StepperControlEncoder::readEncoder() {
void StepperControlEncoder::readEncoder()
{
// save the old values, read the new values
shiftChannels();
@ -94,21 +103,45 @@ void StepperControlEncoder::readEncoder() {
// and check for a position change
// no fancy code, just a few simple compares. sorry
if (prvValChannelA == true && curValChannelA == true && prvValChannelB == false && curValChannelB == true ) {delta++;}
if (prvValChannelA == true && curValChannelA == false && prvValChannelB == true && curValChannelB == true ) {delta++;}
if (prvValChannelA == false && curValChannelA == false && prvValChannelB == true && curValChannelB == false) {delta++;}
if (prvValChannelA == false && curValChannelA == true && prvValChannelB == false && curValChannelB == false) {delta++;}
if (prvValChannelA == false && curValChannelA == false && prvValChannelB == false && curValChannelB == true ) {delta--;}
if (prvValChannelA == false && curValChannelA == true && prvValChannelB == true && curValChannelB == true ) {delta--;}
if (prvValChannelA == true && curValChannelA == true && prvValChannelB == true && curValChannelB == false) {delta--;}
if (prvValChannelA == true && curValChannelA == false && prvValChannelB == false && curValChannelB == false) {delta--;}
position += delta;
if (prvValChannelA == true && curValChannelA == true && prvValChannelB == false && curValChannelB == true)
{
delta++;
}
if (prvValChannelA == true && curValChannelA == false && prvValChannelB == true && curValChannelB == true)
{
delta++;
}
if (prvValChannelA == false && curValChannelA == false && prvValChannelB == true && curValChannelB == false)
{
delta++;
}
if (prvValChannelA == false && curValChannelA == true && prvValChannelB == false && curValChannelB == false)
{
delta++;
}
void StepperControlEncoder::readChannels() {
if (prvValChannelA == false && curValChannelA == false && prvValChannelB == false && curValChannelB == true)
{
delta--;
}
if (prvValChannelA == false && curValChannelA == true && prvValChannelB == true && curValChannelB == true)
{
delta--;
}
if (prvValChannelA == true && curValChannelA == true && prvValChannelB == true && curValChannelB == false)
{
delta--;
}
if (prvValChannelA == true && curValChannelA == false && prvValChannelB == false && curValChannelB == false)
{
delta--;
}
position += delta;
}
void StepperControlEncoder::readChannels()
{
// read the new values from the coder
@ -117,15 +150,18 @@ void StepperControlEncoder::readChannels() {
readChannelB = digitalRead(pinChannelB);
readChannelBQ = digitalRead(pinChannelBQ);
if (encoderType == 1) {
if (encoderType == 1)
{
// differential encoder
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ)) {
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ))
{
curValChannelA = readChannelA;
curValChannelB = readChannelB;
}
}
else {
else
{
// encoderType <= 0
// non-differential incremental encoder
@ -133,16 +169,15 @@ void StepperControlEncoder::readChannels() {
curValChannelB = readChannelB;
}
//curValChannelA = readChannelA;
//curValChannelB = readChannelB;
// curValChannelA = digitalRead(pinChannelA);
// curValChannelB = digitalRead(pinChannelB);
}
void StepperControlEncoder::shiftChannels() {
void StepperControlEncoder::shiftChannels()
{
// Save the current enoder status to later on compare with new values

View File

@ -16,10 +16,10 @@
#include <stdio.h>
#include <stdlib.h>
class StepperControlEncoder {
class StepperControlEncoder
{
public:
StepperControlEncoder();
void loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ);
@ -34,7 +34,6 @@ public:
void test();
private:
// pin settings
int pinChannelA;
int pinChannelAQ;
@ -56,8 +55,6 @@ private:
long position;
int scalingFactor;
int encoderType;
};
#endif /* STEPPERCONTROLENCODER_H_ */

View File

@ -34,9 +34,11 @@ void ftm1_isr(void)
{
uint32_t sc = FTM1_SC;
#ifdef KINETISL
if (sc & 0x80) FTM1_SC = sc;
if (sc & 0x80)
FTM1_SC = sc;
#else
if (sc & 0x80) FTM1_SC = sc & 0x7F;
if (sc & 0x80)
FTM1_SC = sc & 0x7F;
#endif
Timer1.isrCallback();
}

View File

@ -27,49 +27,55 @@
#define TIMER1_RESOLUTION 65536UL // Timer1 is 16 bit
// Placing nearly all the code in this .h file allows the functions to be
// inlined by the compiler. In the very common case with constant values
// the compiler will perform all calculations and simply write constants
// to the hardware registers (for example, setPeriod).
class TimerOne
{
#if defined(__AVR__)
public:
//****************************
// Configuration
//****************************
void initialize(unsigned long microseconds=1000000) __attribute__((always_inline)) {
void initialize(unsigned long microseconds = 1000000) __attribute__((always_inline))
{
TCCR1B = _BV(WGM13); // set mode as phase and frequency correct pwm, stop the timer
TCCR1A = 0; // clear control register A
setPeriod(microseconds);
}
void setPeriod(unsigned long microseconds) __attribute__((always_inline)) {
void setPeriod(unsigned long microseconds) __attribute__((always_inline))
{
const unsigned long cycles = (F_CPU / 2000000) * microseconds;
if (cycles < TIMER1_RESOLUTION) {
if (cycles < TIMER1_RESOLUTION)
{
clockSelectBits = _BV(CS10);
pwmPeriod = cycles;
} else
if (cycles < TIMER1_RESOLUTION * 8) {
}
else if (cycles < TIMER1_RESOLUTION * 8)
{
clockSelectBits = _BV(CS11);
pwmPeriod = cycles / 8;
} else
if (cycles < TIMER1_RESOLUTION * 64) {
}
else if (cycles < TIMER1_RESOLUTION * 64)
{
clockSelectBits = _BV(CS11) | _BV(CS10);
pwmPeriod = cycles / 64;
} else
if (cycles < TIMER1_RESOLUTION * 256) {
}
else if (cycles < TIMER1_RESOLUTION * 256)
{
clockSelectBits = _BV(CS12);
pwmPeriod = cycles / 256;
} else
if (cycles < TIMER1_RESOLUTION * 1024) {
}
else if (cycles < TIMER1_RESOLUTION * 1024)
{
clockSelectBits = _BV(CS12) | _BV(CS10);
pwmPeriod = cycles / 1024;
} else {
}
else
{
clockSelectBits = _BV(CS12) | _BV(CS10);
pwmPeriod = TIMER1_RESOLUTION - 1;
}
@ -80,73 +86,104 @@ class TimerOne
//****************************
// Run Control
//****************************
void start() __attribute__((always_inline)) {
void start() __attribute__((always_inline))
{
TCCR1B = 0;
TCNT1 = 0; // TODO: does this cause an undesired interrupt?
resume();
}
void stop() __attribute__((always_inline)) {
void stop() __attribute__((always_inline))
{
TCCR1B = _BV(WGM13);
}
void restart() __attribute__((always_inline)) {
void restart() __attribute__((always_inline))
{
start();
}
void resume() __attribute__((always_inline)) {
void resume() __attribute__((always_inline))
{
TCCR1B = _BV(WGM13) | clockSelectBits;
}
//****************************
// PWM outputs
//****************************
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline)) {
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline))
{
unsigned long dutyCycle = pwmPeriod;
dutyCycle *= duty;
dutyCycle >>= 10;
if (pin == TIMER1_A_PIN) OCR1A = dutyCycle;
if (pin == TIMER1_A_PIN)
OCR1A = dutyCycle;
#ifdef TIMER1_B_PIN
else if (pin == TIMER1_B_PIN) OCR1B = dutyCycle;
else if (pin == TIMER1_B_PIN)
OCR1B = dutyCycle;
#endif
#ifdef TIMER1_C_PIN
else if (pin == TIMER1_C_PIN) OCR1C = dutyCycle;
else if (pin == TIMER1_C_PIN)
OCR1C = dutyCycle;
#endif
}
void pwm(char pin, unsigned int duty) __attribute__((always_inline)) {
if (pin == TIMER1_A_PIN) { pinMode(TIMER1_A_PIN, OUTPUT); TCCR1A |= _BV(COM1A1); }
void pwm(char pin, unsigned int duty) __attribute__((always_inline))
{
if (pin == TIMER1_A_PIN)
{
pinMode(TIMER1_A_PIN, OUTPUT);
TCCR1A |= _BV(COM1A1);
}
#ifdef TIMER1_B_PIN
else if (pin == TIMER1_B_PIN) { pinMode(TIMER1_B_PIN, OUTPUT); TCCR1A |= _BV(COM1B1); }
else if (pin == TIMER1_B_PIN)
{
pinMode(TIMER1_B_PIN, OUTPUT);
TCCR1A |= _BV(COM1B1);
}
#endif
#ifdef TIMER1_C_PIN
else if (pin == TIMER1_C_PIN) { pinMode(TIMER1_C_PIN, OUTPUT); TCCR1A |= _BV(COM1C1); }
else if (pin == TIMER1_C_PIN)
{
pinMode(TIMER1_C_PIN, OUTPUT);
TCCR1A |= _BV(COM1C1);
}
#endif
setPwmDuty(pin, duty);
TCCR1B = _BV(WGM13) | clockSelectBits;
}
void pwm(char pin, unsigned int duty, unsigned long microseconds) __attribute__((always_inline)) {
if (microseconds > 0) setPeriod(microseconds);
void pwm(char pin, unsigned int duty, unsigned long microseconds) __attribute__((always_inline))
{
if (microseconds > 0)
setPeriod(microseconds);
pwm(pin, duty);
}
void disablePwm(char pin) __attribute__((always_inline)) {
if (pin == TIMER1_A_PIN) TCCR1A &= ~_BV(COM1A1);
void disablePwm(char pin) __attribute__((always_inline))
{
if (pin == TIMER1_A_PIN)
TCCR1A &= ~_BV(COM1A1);
#ifdef TIMER1_B_PIN
else if (pin == TIMER1_B_PIN) TCCR1A &= ~_BV(COM1B1);
else if (pin == TIMER1_B_PIN)
TCCR1A &= ~_BV(COM1B1);
#endif
#ifdef TIMER1_C_PIN
else if (pin == TIMER1_C_PIN) TCCR1A &= ~_BV(COM1C1);
else if (pin == TIMER1_C_PIN)
TCCR1A &= ~_BV(COM1C1);
#endif
}
//****************************
// Interrupt Function
//****************************
void attachInterrupt(void (*isr)()) __attribute__((always_inline)) {
void attachInterrupt(void (*isr)()) __attribute__((always_inline))
{
isrCallback = isr;
TIMSK1 = _BV(TOIE1);
}
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline)) {
if(microseconds > 0) setPeriod(microseconds);
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline))
{
if (microseconds > 0)
setPeriod(microseconds);
attachInterrupt(isr);
}
void detachInterrupt() __attribute__((always_inline)) {
void detachInterrupt() __attribute__((always_inline))
{
TIMSK1 = 0;
}
static void (*isrCallback)();
@ -156,11 +193,6 @@ class TimerOne
static unsigned short pwmPeriod;
static unsigned char clockSelectBits;
#elif defined(__arm__) && defined(CORE_TEENSY)
#if defined(KINETISK)
@ -173,43 +205,55 @@ class TimerOne
//****************************
// Configuration
//****************************
void initialize(unsigned long microseconds=1000000) __attribute__((always_inline)) {
void initialize(unsigned long microseconds = 1000000) __attribute__((always_inline))
{
setPeriod(microseconds);
}
void setPeriod(unsigned long microseconds) __attribute__((always_inline)) {
void setPeriod(unsigned long microseconds) __attribute__((always_inline))
{
const unsigned long cycles = (F_TIMER / 2000000) * microseconds;
if (cycles < TIMER1_RESOLUTION) {
if (cycles < TIMER1_RESOLUTION)
{
clockSelectBits = 0;
pwmPeriod = cycles;
} else
if (cycles < TIMER1_RESOLUTION * 2) {
}
else if (cycles < TIMER1_RESOLUTION * 2)
{
clockSelectBits = 1;
pwmPeriod = cycles >> 1;
} else
if (cycles < TIMER1_RESOLUTION * 4) {
}
else if (cycles < TIMER1_RESOLUTION * 4)
{
clockSelectBits = 2;
pwmPeriod = cycles >> 2;
} else
if (cycles < TIMER1_RESOLUTION * 8) {
}
else if (cycles < TIMER1_RESOLUTION * 8)
{
clockSelectBits = 3;
pwmPeriod = cycles >> 3;
} else
if (cycles < TIMER1_RESOLUTION * 16) {
}
else if (cycles < TIMER1_RESOLUTION * 16)
{
clockSelectBits = 4;
pwmPeriod = cycles >> 4;
} else
if (cycles < TIMER1_RESOLUTION * 32) {
}
else if (cycles < TIMER1_RESOLUTION * 32)
{
clockSelectBits = 5;
pwmPeriod = cycles >> 5;
} else
if (cycles < TIMER1_RESOLUTION * 64) {
}
else if (cycles < TIMER1_RESOLUTION * 64)
{
clockSelectBits = 6;
pwmPeriod = cycles >> 6;
} else
if (cycles < TIMER1_RESOLUTION * 128) {
}
else if (cycles < TIMER1_RESOLUTION * 128)
{
clockSelectBits = 7;
pwmPeriod = cycles >> 7;
} else {
}
else
{
clockSelectBits = 7;
pwmPeriod = TIMER1_RESOLUTION - 1;
}
@ -222,50 +266,68 @@ class TimerOne
//****************************
// Run Control
//****************************
void start() __attribute__((always_inline)) {
void start() __attribute__((always_inline))
{
stop();
FTM1_CNT = 0;
resume();
}
void stop() __attribute__((always_inline)) {
void stop() __attribute__((always_inline))
{
FTM1_SC = FTM1_SC & (FTM_SC_TOIE | FTM_SC_CPWMS | FTM_SC_PS(7));
}
void restart() __attribute__((always_inline)) {
void restart() __attribute__((always_inline))
{
start();
}
void resume() __attribute__((always_inline)) {
void resume() __attribute__((always_inline))
{
FTM1_SC = (FTM1_SC & (FTM_SC_TOIE | FTM_SC_PS(7))) | FTM_SC_CPWMS | FTM_SC_CLKS(1);
}
//****************************
// PWM outputs
//****************************
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline)) {
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline))
{
unsigned long dutyCycle = pwmPeriod;
dutyCycle *= duty;
dutyCycle >>= 10;
if (pin == TIMER1_A_PIN) {
if (pin == TIMER1_A_PIN)
{
FTM1_C0V = dutyCycle;
} else if (pin == TIMER1_B_PIN) {
}
else if (pin == TIMER1_B_PIN)
{
FTM1_C1V = dutyCycle;
}
}
void pwm(char pin, unsigned int duty) __attribute__((always_inline)) {
void pwm(char pin, unsigned int duty) __attribute__((always_inline))
{
setPwmDuty(pin, duty);
if (pin == TIMER1_A_PIN) {
if (pin == TIMER1_A_PIN)
{
*portConfigRegister(TIMER1_A_PIN) = PORT_PCR_MUX(3) | PORT_PCR_DSE | PORT_PCR_SRE;
} else if (pin == TIMER1_B_PIN) {
}
else if (pin == TIMER1_B_PIN)
{
*portConfigRegister(TIMER1_B_PIN) = PORT_PCR_MUX(3) | PORT_PCR_DSE | PORT_PCR_SRE;
}
}
void pwm(char pin, unsigned int duty, unsigned long microseconds) __attribute__((always_inline)) {
if (microseconds > 0) setPeriod(microseconds);
void pwm(char pin, unsigned int duty, unsigned long microseconds) __attribute__((always_inline))
{
if (microseconds > 0)
setPeriod(microseconds);
pwm(pin, duty);
}
void disablePwm(char pin) __attribute__((always_inline)) {
if (pin == TIMER1_A_PIN) {
void disablePwm(char pin) __attribute__((always_inline))
{
if (pin == TIMER1_A_PIN)
{
*portConfigRegister(TIMER1_A_PIN) = 0;
} else if (pin == TIMER1_B_PIN) {
}
else if (pin == TIMER1_B_PIN)
{
*portConfigRegister(TIMER1_B_PIN) = 0;
}
}
@ -273,16 +335,20 @@ class TimerOne
//****************************
// Interrupt Function
//****************************
void attachInterrupt(void (*isr)()) __attribute__((always_inline)) {
void attachInterrupt(void (*isr)()) __attribute__((always_inline))
{
isrCallback = isr;
FTM1_SC |= FTM_SC_TOIE;
NVIC_ENABLE_IRQ(IRQ_FTM1);
}
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline)) {
if(microseconds > 0) setPeriod(microseconds);
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline))
{
if (microseconds > 0)
setPeriod(microseconds);
attachInterrupt(isr);
}
void detachInterrupt() __attribute__((always_inline)) {
void detachInterrupt() __attribute__((always_inline))
{
FTM1_SC &= ~FTM_SC_TOIE;
NVIC_DISABLE_IRQ(IRQ_FTM1);
}
@ -301,4 +367,3 @@ class TimerOne
extern TimerOne Timer1;
#endif

View File

@ -8,7 +8,6 @@
#include "TimerOne.h"
#include "MemoryFree.h"
static char commandEndChar = 0x0A;
static GCodeProcessor *gCodeProcessor = new GCodeProcessor();
@ -25,7 +24,8 @@ int incomingCommandPointer = 0;
// Blink led routine used for testing
bool blink = false;
void blinkLed() {
void blinkLed()
{
blink = !blink;
digitalWrite(LED_PIN, blink);
}
@ -37,16 +37,19 @@ void blinkLed() {
//
bool interruptBusy = false;
int interruptSecondTimer = 0;
void interrupt(void) {
void interrupt(void)
{
interruptSecondTimer++;
if (interruptBusy == false) {
if (interruptBusy == false)
{
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
// Check the actions triggered once per second
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED) {
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED)
{
interruptSecondTimer = 0;
PinGuard::getInstance()->checkPins();
//blinkLed();
@ -56,9 +59,9 @@ void interrupt(void) {
}
}
//The setup function is called once at startup of the sketch
void setup() {
void setup()
{
// Setup pin input/output settings
pinMode(X_STEP_PIN, OUTPUT);
@ -121,9 +124,11 @@ void setup() {
}
// The loop function is called in an endless loop
void loop() {
void loop()
{
if (Serial.available()) {
if (Serial.available())
{
// Save current time stamp for timeout actions
lastAction = millis();
@ -134,13 +139,15 @@ void loop() {
incomingCommandPointer++;
// If the string is getting to long, cap it off with a new line and let it process anyway
if (incomingCommandPointer >= INCOMING_CMD_BUF_SIZE - 1) {
if (incomingCommandPointer >= INCOMING_CMD_BUF_SIZE - 1)
{
incomingChar = '\n';
incomingCommandArray[incomingCommandPointer] = incomingChar;
incomingCommandPointer++;
}
if (incomingChar == '\n' || incomingCommandPointer >= INCOMING_CMD_BUF_SIZE) {
if (incomingChar == '\n' || incomingCommandPointer >= INCOMING_CMD_BUF_SIZE)
{
//commandString += incomingChar;
//String commandString = Serial.readStringUntil(commandEndChar);
@ -148,13 +155,14 @@ void loop() {
//currentCommand.toCharArray(commandChar, currentCommand.length());
char commandChar[incomingCommandPointer + 1];
for (int i = 0; i < incomingCommandPointer -1; i++) {
for (int i = 0; i < incomingCommandPointer - 1; i++)
{
commandChar[i] = incomingCommandArray[i];
}
commandChar[incomingCommandPointer] = 0;
if (incomingCommandPointer > 1) {
if (incomingCommandPointer > 1)
{
// Copy the command to another string object.
// because there are issues with passing the
@ -164,7 +172,8 @@ void loop() {
//Command* command = new Command(commandString);
Command *command = new Command(commandChar);
if(LOGGING) {
if (LOGGING)
{
command->print();
}
@ -181,7 +190,8 @@ void loop() {
// Check if parameters are changes, and if so load the new settings
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber()) {
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber())
{
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();
Serial.print(COMM_REPORT_COMMENT);
@ -192,18 +202,20 @@ void loop() {
PinGuard::getInstance()->loadConfig();
}
// Do periodic checks and feedback
currentTime = millis();
if (currentTime < lastAction) {
if (currentTime < lastAction)
{
// If the device timer overruns, reset the idle counter
lastAction = millis();
}
else {
else
{
if ((currentTime - lastAction) > 5000) {
if ((currentTime - lastAction) > 5000)
{
// After an idle time, send the idle message
Serial.print(COMM_REPORT_CMD_IDLE);
@ -229,7 +241,6 @@ void loop() {
//ParameterList::getInstance()->readAllValues();
//StepperControl::getInstance()->test();
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
@ -241,4 +252,3 @@ void loop() {
}
}
}

View File

@ -25,6 +25,5 @@ void setup();
//Do not add code below this line
#endif /* _farmbot_arduino_controller_H_ */