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

2
.gitignore vendored
View File

@ -25,4 +25,4 @@
/.build
/.vs
/src/Debug
/src/__vm
/src/__vm

View File

@ -18,4 +18,4 @@ FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
SOFTWARE.

View File

@ -95,7 +95,7 @@ X_MIN_PIN | 3 | X axis end stop at home position
X_MAX_PIN | 2 | X axis end stop at far position
X_ENCDR_A | 16 | X axis encoder A channel
X_ENCDR_B | 17 | X axis encoder B channel
X_ENCDR_A_Q | 31 | X axis encoder A channel for quarature (not implemented)
X_ENCDR_A_Q | 31 | X axis encoder A channel for quarature (not implemented)
X_ENCDR_B_Q | 33 | X axis encoder B channel for quarature (not implemented)
Y_STEP_PIN | 60 | Y axis step signal
Y_DIR_PIN | 61 | Y axis direction choice
@ -104,8 +104,8 @@ Y_MIN_PIN | 14 | Y axis end stop at home position
Y_MAX_PIN | 15 | Y axis end stop at far position
Y_ENCDR_A | 23 | Y axis encoder A channel
Y_ENCDR_B | 25 | Y axis encoder B channel
Y_ENCDR_A_Q | 35 | Y axis encoder A channel for quarature (not implemented)
Y_ENCDR_B_Q | 37 | Y axis encoder B channel for quarature (not implemented)
Y_ENCDR_A_Q | 35 | Y axis encoder A channel for quarature (not implemented)
Y_ENCDR_B_Q | 37 | Y axis encoder B channel for quarature (not implemented)
Z_STEP_PIN | 46 | Z axis step signal
Z_DIR_PIN | 48 | Z axis direction choice
Z_ENABLE_PIN | 62 | Z axis enable
@ -113,8 +113,8 @@ Z_MIN_PIN | 18 | Z axis end stop at home position
Z_MAX_PIN | 19 | Z axis end stop at far position
Z_ENCDR_A | 27 | Z axis encoder A channel
Z_ENCDR_B | 29 | Z axis encoder B channel
Z_ENCDR_A_Q | 39 | Z axis encoder A channel for quarature (not implemented)
Z_ENCDR_B_Q | 41 | Z axis encoder B channel for quarature (not implemented)
Z_ENCDR_A_Q | 39 | Z axis encoder A channel for quarature (not implemented)
Z_ENCDR_B_Q | 41 | Z axis encoder B channel for quarature (not implemented)
LED_PIN | 13 | on board LED
FAN_PIN | 9 | RAMPS board fan pin
HEATER_0_PIN | 10 | RAMPS board heating pin 0
@ -150,7 +150,7 @@ F |31 |P |Read status
F |32 |P V |Write status
F |41 |P V M |Set a value V on an arduino pin in mode M (digital=0/analog=1)
F |42 |P M |Read a value from an arduino pin P in mode M (digital=0/analog=1)
F |43 |P M |Set the I/O mode M (input=0/output=1) of a pin P in arduino
F |43 |P M |Set the I/O mode M (input=0/output=1) of a pin P in arduino
F |44 |P V W T M |Set the value V on an arduino pin P, wait for time T in milliseconds, set value W on the arduino pin P in mode M (digital=0/analog=1)
F |51 |E P V |Set a value on the tool mount with I2C (not implemented)
F |52 |E P |Read value from the tool mount with I2C (not implemented)

View File

@ -1,276 +1,333 @@
#include "Command.h"
const char axisCodes[3] = { 'X', 'Y', 'Z' };
const char axisSpeedCodes[3] = { 'A', 'B', 'C' };
const char speedCode = 'S';
const char parameterIdCode = 'P';
const char axisCodes[3] = {'X', 'Y', 'Z'};
const char axisSpeedCodes[3] = {'A', 'B', 'C'};
const char speedCode = 'S';
const char parameterIdCode = 'P';
const char parameterValueCode = 'V';
const char parameterValue2Code= 'W';
const char elementCode = 'E';
const char timeCode = 'T';
const char modeCode = 'M';
const char msgQueueCode = 'Q';
const char parameterValue2Code = 'W';
const char elementCode = 'E';
const char timeCode = 'T';
const char modeCode = 'M';
const char msgQueueCode = 'Q';
CommandCodeEnum commandCodeEnum = CODE_UNDEFINED;
Command::Command(char * commandChar) {
Command::Command(char *commandChar)
{
char * charBuf = commandChar;
char* charPointer;
bool invalidCommand = false;
char *charBuf = commandChar;
char *charPointer;
bool invalidCommand = false;
charPointer = strtok(charBuf, " \n\r");
charPointer = strtok(charBuf, " \n\r");
if (charPointer[0] == 'G' || charPointer[0] == 'F') {
commandCodeEnum = getGCodeEnum(charPointer);
} else {
invalidCommand = true;
return;
}
if (charPointer[0] == 'G' || charPointer[0] == 'F')
{
commandCodeEnum = getGCodeEnum(charPointer);
}
else
{
invalidCommand = true;
return;
}
while (charPointer != NULL) {
getParameter(charPointer);
while (charPointer != NULL)
{
getParameter(charPointer);
charPointer = strtok(NULL, " \n\r");
}
charPointer = strtok(NULL, " \n\r");
}
}
CommandCodeEnum Command::getGCodeEnum(char* code) {
CommandCodeEnum Command::getGCodeEnum(char *code)
{
if (strcmp(code, "G0") == 0 || strcmp(code, "G00") == 0)
{
return G00;
}
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, "G0") == 0 || strcmp(code, "G00") == 0) {
return G00;
}
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)
{
return F11;
}
if (strcmp(code, "F12") == 0)
{
return F12;
}
if (strcmp(code, "F13") == 0)
{
return F13;
}
if (strcmp(code, "F14") == 0)
{
return F14;
}
if (strcmp(code, "F15") == 0)
{
return F15;
}
if (strcmp(code, "F16") == 0)
{
return F16;
}
if (strcmp(code, "F11") == 0) {
return F11;
}
if (strcmp(code, "F12") == 0) {
return F12;
}
if (strcmp(code, "F13") == 0) {
return F13;
}
if (strcmp(code, "F14") == 0) {
return F14;
}
if (strcmp(code, "F15") == 0) {
return F15;
}
if (strcmp(code, "F16") == 0) {
return F16;
}
if (strcmp(code, "F20") == 0)
{
return F20;
}
if (strcmp(code, "F21") == 0)
{
return F21;
}
if (strcmp(code, "F22") == 0)
{
return F22;
}
if (strcmp(code, "F20") == 0) {
return F20;
}
if (strcmp(code, "F21") == 0) {
return F21;
}
if (strcmp(code, "F22") == 0) {
return F22;
}
if (strcmp(code, "F31") == 0)
{
return F31;
}
if (strcmp(code, "F32") == 0)
{
return F32;
}
if (strcmp(code, "F31") == 0) {
return F31;
}
if (strcmp(code, "F32") == 0) {
return F32;
}
if (strcmp(code, "F41") == 0)
{
return F41;
}
if (strcmp(code, "F42") == 0)
{
return F42;
}
if (strcmp(code, "F43") == 0)
{
return F43;
}
if (strcmp(code, "F44") == 0)
{
return F44;
}
if (strcmp(code, "F41") == 0) {
return F41;
}
if (strcmp(code, "F42") == 0) {
return F42;
}
if (strcmp(code, "F43") == 0) {
return F43;
}
if (strcmp(code, "F44") == 0) {
return F44;
}
if (strcmp(code, "F61") == 0)
{
return F61;
}
if (strcmp(code, "F61") == 0) {
return F61;
}
if (strcmp(code, "F81") == 0)
{
return F81;
}
if (strcmp(code, "F82") == 0)
{
return F82;
}
if (strcmp(code, "F83") == 0)
{
return F83;
}
if (strcmp(code, "F84") == 0)
{
return F84;
}
if (strcmp(code, "F81") == 0) {
return F81;
}
if (strcmp(code, "F82") == 0) {
return F82;
}
if (strcmp(code, "F83") == 0) {
return F83;
}
if (strcmp(code, "F84") == 0) {
return F84;
}
return CODE_UNDEFINED;
return CODE_UNDEFINED;
}
double minusNotAllowed(double value) {
if(value < 0) {
return 0;
}
return value;
double minusNotAllowed(double value)
{
if (value < 0)
{
return 0;
}
return value;
}
void Command::getParameter(char* charPointer) {
void Command::getParameter(char *charPointer)
{
//msgQueue = 24;
//msgQueue = 24;
if (charPointer[0] == axisCodes[0] ){
axisValue[0] = atof(charPointer + 1 );
//msgQueue = 77;
}
if (charPointer[0] == axisCodes[0])
{
axisValue[0] = atof(charPointer + 1);
//msgQueue = 77;
}
if (charPointer[0] == axisCodes[1] ){
axisValue[1] = atof(charPointer + 1 );
}
if (charPointer[0] == axisCodes[1])
{
axisValue[1] = atof(charPointer + 1);
}
if (charPointer[0] == axisCodes[2] ){
axisValue[2] = atof(charPointer + 1 );
}
if (charPointer[0] == axisCodes[2])
{
axisValue[2] = atof(charPointer + 1);
}
if (charPointer[0] == axisSpeedCodes[0] ){
axisSpeedValue[0] = atof(charPointer + 1 );
}
if (charPointer[0] == axisSpeedCodes[0])
{
axisSpeedValue[0] = atof(charPointer + 1);
}
if (charPointer[0] == axisSpeedCodes[1] ){
axisSpeedValue[1] = atof(charPointer + 1 );
}
if (charPointer[0] == axisSpeedCodes[1])
{
axisSpeedValue[1] = atof(charPointer + 1);
}
if (charPointer[0] == axisSpeedCodes[2] ){
axisSpeedValue[2] = atof(charPointer + 1 );
}
if (charPointer[0] == axisSpeedCodes[2])
{
axisSpeedValue[2] = atof(charPointer + 1);
}
if (charPointer[0] == speedCode ){
speedValue = atof(charPointer + 1 );
}
if (charPointer[0] == speedCode)
{
speedValue = atof(charPointer + 1);
}
if (charPointer[0] == parameterIdCode ){
parameterId = atof(charPointer + 1 );
}
if (charPointer[0] == parameterIdCode)
{
parameterId = atof(charPointer + 1);
}
if (charPointer[0] == parameterValueCode ){
parameterValue = atof(charPointer + 1 );
if (charPointer[0] == parameterValueCode)
{
parameterValue = atof(charPointer + 1);
}
}
if (charPointer[0] == parameterValue2Code)
{
parameterValue2 = atof(charPointer + 1);
}
if (charPointer[0] == parameterValue2Code ){
parameterValue2 = atof(charPointer + 1 );
}
if (charPointer[0] == elementCode)
{
element = atof(charPointer + 1);
}
if (charPointer[0] == elementCode ){
element = atof(charPointer + 1 );
}
if (charPointer[0] == timeCode)
{
time = atof(charPointer + 1);
}
if (charPointer[0] == timeCode ){
time = atof(charPointer + 1 );
}
if (charPointer[0] == modeCode)
{
mode = atof(charPointer + 1);
}
if (charPointer[0] == modeCode ){
mode = atof(charPointer + 1 );
}
if (charPointer[0] == msgQueueCode ){
msgQueue = atof(charPointer + 1 );
//msgQueue = 5;
}
if (charPointer[0] == msgQueueCode)
{
msgQueue = atof(charPointer + 1);
//msgQueue = 5;
}
}
void Command::print() {
Serial.print("R99 Command with code: ");
Serial.print(commandCodeEnum);
Serial.print(", X: ");
Serial.print(axisValue[0]);
Serial.print(", Y: ");
Serial.print(axisValue[1]);
Serial.print(", Z: ");
Serial.print(axisValue[2]);
Serial.print(", S: ");
Serial.print(speedValue);
Serial.print(", P: ");
Serial.print(parameterId);
Serial.print(", V: ");
Serial.print(parameterValue);
void Command::print()
{
Serial.print("R99 Command with code: ");
Serial.print(commandCodeEnum);
Serial.print(", X: ");
Serial.print(axisValue[0]);
Serial.print(", Y: ");
Serial.print(axisValue[1]);
Serial.print(", Z: ");
Serial.print(axisValue[2]);
Serial.print(", S: ");
Serial.print(speedValue);
Serial.print(", P: ");
Serial.print(parameterId);
Serial.print(", V: ");
Serial.print(parameterValue);
Serial.print(", W: ");
Serial.print(parameterValue2);
Serial.print(", T: ");
Serial.print(time);
Serial.print(", E: ");
Serial.print(element);
Serial.print(", M: ");
Serial.print(mode);
Serial.print(", Q: ");
Serial.print(msgQueue);
Serial.print("\r\n");
Serial.print(", W: ");
Serial.print(parameterValue2);
Serial.print(", T: ");
Serial.print(time);
Serial.print(", E: ");
Serial.print(element);
Serial.print(", M: ");
Serial.print(mode);
Serial.print(", Q: ");
Serial.print(msgQueue);
Serial.print("\r\n");
}
CommandCodeEnum Command::getCodeEnum() {
return commandCodeEnum;
CommandCodeEnum Command::getCodeEnum()
{
return commandCodeEnum;
}
double Command::getX() {
return axisValue[0];
double Command::getX()
{
return axisValue[0];
}
double Command::getY() {
return axisValue[1];
double Command::getY()
{
return axisValue[1];
}
double Command::getZ() {
return axisValue[2];
double Command::getZ()
{
return axisValue[2];
}
long Command::getA() {
return axisSpeedValue[0];
long Command::getA()
{
return axisSpeedValue[0];
}
long Command::getB() {
return axisSpeedValue[1];
long Command::getB()
{
return axisSpeedValue[1];
}
long Command::getC() {
return axisSpeedValue[2];
long Command::getC()
{
return axisSpeedValue[2];
}
long Command::getP() {
return parameterId;
long Command::getP()
{
return parameterId;
}
long Command::getV() {
return parameterValue;
long Command::getV()
{
return parameterValue;
}
long Command::getW() {
return parameterValue2;
long Command::getW()
{
return parameterValue2;
}
long Command::getT() {
return time;
long Command::getT()
{
return time;
}
long Command::getE() {
return element;
long Command::getE()
{
return element;
}
long Command::getM() {
return mode;
long Command::getM()
{
return mode;
}
long Command::getQ() {
//msgQueue = 9876;
return msgQueue;
long Command::getQ()
{
//msgQueue = 9876;
return msgQueue;
}

View File

@ -7,9 +7,9 @@
enum CommandCodeEnum
{
CODE_UNDEFINED = -1,
G00 = 0,
G01 = 1,
G28 = 28,
G00 = 0,
G01 = 1,
G28 = 28,
F01 = 101,
F02 = 102,
F03 = 103,
@ -37,44 +37,46 @@ enum CommandCodeEnum
//#define NULL 0
class Command {
CommandCodeEnum codeEnum;
class Command
{
CommandCodeEnum codeEnum;
public:
// Command(String);
Command(char * commandChar);
void print();
CommandCodeEnum getCodeEnum();
double getX();
double getY();
double getZ();
double getS();
long getP();
long getV();
long getA();
long getB();
long getC();
long getW();
long getT();
long getE();
long getM();
long getQ();
// Command(String);
Command(char *commandChar);
void print();
CommandCodeEnum getCodeEnum();
double getX();
double getY();
double getZ();
double getS();
long getP();
long getV();
long getA();
long getB();
long getC();
long getW();
long getT();
long getE();
long getM();
long getQ();
void printQAndNewLine();
void printQAndNewLine();
private:
CommandCodeEnum getGCodeEnum(char* code);
void getParameter(char* charPointer);
double axisValue[3] = { 0.0, 0.0, 0.0 };
long axisSpeedValue[3] = { 0, 0, 0 };
double speedValue = 0.0;
long parameterId = 0;
long parameterValue = 0;
long parameterValue2 = 0;
long element = 0;
long time = 0;
long mode = 0;
long msgQueue = 0;
CommandCodeEnum getGCodeEnum(char *code);
void getParameter(char *charPointer);
double axisValue[3] = {0.0, 0.0, 0.0};
long axisSpeedValue[3] = {0, 0, 0};
double speedValue = 0.0;
long parameterId = 0;
long parameterValue = 0;
long parameterValue2 = 0;
long element = 0;
long time = 0;
long mode = 0;
long msgQueue = 0;
};
#endif /* COMMAND_H_ */

View File

@ -22,130 +22,128 @@ const String COMM_REPORT_CMD_STATUS = "R05";
const String COMM_REPORT_CALIB_STATUS = "R06";
*/
const char COMM_REPORT_CMD_IDLE[4] = {'R','0','0','\0'};
const char COMM_REPORT_CMD_START[4] = {'R','0','1','\0'};
const char COMM_REPORT_CMD_DONE[4] = {'R','0','2','\0'};
const char COMM_REPORT_CMD_ERROR[4] = {'R','0','3','\0'};
const char COMM_REPORT_CMD_BUSY[4] = {'R','0','4','\0'};
const char COMM_REPORT_CMD_STATUS[4] = {'R','0','5','\0'};
const char COMM_REPORT_CALIB_STATUS[4] = {'R','0','6','\0'};
const char COMM_REPORT_NO_CONFIG[4] = {'R','8','8','\0'};
const char COMM_REPORT_COMMENT[4] = {'R','9','9','\0'};
const char COMM_REPORT_CMD_IDLE[4] = {'R', '0', '0', '\0'};
const char COMM_REPORT_CMD_START[4] = {'R', '0', '1', '\0'};
const char COMM_REPORT_CMD_DONE[4] = {'R', '0', '2', '\0'};
const char COMM_REPORT_CMD_ERROR[4] = {'R', '0', '3', '\0'};
const char COMM_REPORT_CMD_BUSY[4] = {'R', '0', '4', '\0'};
const char COMM_REPORT_CMD_STATUS[4] = {'R', '0', '5', '\0'};
const char COMM_REPORT_CALIB_STATUS[4] = {'R', '0', '6', '\0'};
const char COMM_REPORT_NO_CONFIG[4] = {'R', '8', '8', '\0'};
const char COMM_REPORT_COMMENT[4] = {'R', '9', '9', '\0'};
const int COMM_REPORT_MOVE_STATUS_IDLE = 0;
const int COMM_REPORT_MOVE_STATUS_START_MOTOR = 1;
const int COMM_REPORT_MOVE_STATUS_ACCELERATING = 2;
const int COMM_REPORT_MOVE_STATUS_CRUISING = 3;
const int COMM_REPORT_MOVE_STATUS_DECELERATING = 4;
const int COMM_REPORT_MOVE_STATUS_STOP_MOTOR = 5;
const int COMM_REPORT_MOVE_STATUS_CRAWLING = 6;
const int COMM_REPORT_MOVE_STATUS_ERROR = -1;
const int COMM_REPORT_CALIBRATE_STATUS_IDLE = 0;
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 COMM_REPORT_MOVE_STATUS_IDLE = 0;
const int COMM_REPORT_MOVE_STATUS_START_MOTOR = 1;
const int COMM_REPORT_MOVE_STATUS_ACCELERATING = 2;
const int COMM_REPORT_MOVE_STATUS_CRUISING = 3;
const int COMM_REPORT_MOVE_STATUS_DECELERATING = 4;
const int COMM_REPORT_MOVE_STATUS_STOP_MOTOR = 5;
const int COMM_REPORT_MOVE_STATUS_CRAWLING = 6;
const int COMM_REPORT_MOVE_STATUS_ERROR = -1;
const int COMM_REPORT_CALIBRATE_STATUS_IDLE = 0;
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;
const unsigned int MOVEMENT_DELAY = 250;
const unsigned int MOVEMENT_SPEED_BASE_TIME = 2000;
const unsigned int MOVEMENT_DELAY = 250;
const long PARAM_VERSION_DEFAULT = 1;
const long PARAM_TEST_DEFAULT = 0;
const long PARAM_VERSION_DEFAULT = 1;
const long PARAM_TEST_DEFAULT = 0;
const long PARAM_CONFIG_OK_DEFAULT = 0;
const long PARAM_USE_EEPROM_DEFAULT = 1;
const long PARAM_CONFIG_OK_DEFAULT = 0;
const long PARAM_USE_EEPROM_DEFAULT = 1;
const long MOVEMENT_TIMEOUT_X_DEFAULT = 120;
const long MOVEMENT_TIMEOUT_Y_DEFAULT = 120;
const long MOVEMENT_TIMEOUT_Z_DEFAULT = 120;
const long MOVEMENT_TIMEOUT_X_DEFAULT = 120;
const long MOVEMENT_TIMEOUT_Y_DEFAULT = 120;
const long MOVEMENT_TIMEOUT_Z_DEFAULT = 120;
const long MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT = 0;
const long MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_X_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_Y_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_Z_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_X_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_Y_DEFAULT = 0;
const long MOVEMENT_INVERT_MOTOR_Z_DEFAULT = 0;
const long MOVEMENT_SECONDARY_MOTOR_X_DEFAULT = 1;
const long MOVEMENT_SECONDARY_MOTOR_INVERT_X_DEFAULT = 0;
const long MOVEMENT_SECONDARY_MOTOR_X_DEFAULT = 1;
const long MOVEMENT_SECONDARY_MOTOR_INVERT_X_DEFAULT = 0;
const long MOVEMENT_HOME_UP_X_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Y_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Z_DEFAULT = 1;
const long MOVEMENT_HOME_UP_X_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Y_DEFAULT = 0;
const long MOVEMENT_HOME_UP_Z_DEFAULT = 1;
// numver of steps used for acceleration or deceleration
const long MOVEMENT_STEPS_ACC_DEC_X_DEFAULT = 500;
const long MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT = 500;
const long MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT = 500;
const long MOVEMENT_STEPS_ACC_DEC_X_DEFAULT = 500;
const long MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT = 500;
const long MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT = 500;
// Minimum speed in steps per second
const long MOVEMENT_MIN_SPD_X_DEFAULT = 50;
const long MOVEMENT_MIN_SPD_Y_DEFAULT = 50;
const long MOVEMENT_MIN_SPD_Z_DEFAULT = 50;
const long MOVEMENT_MIN_SPD_X_DEFAULT = 50;
const long MOVEMENT_MIN_SPD_Y_DEFAULT = 50;
const long MOVEMENT_MIN_SPD_Z_DEFAULT = 50;
// Maxumum speed in steps per second
const long MOVEMENT_MAX_SPD_X_DEFAULT = 800;
const long MOVEMENT_MAX_SPD_Y_DEFAULT = 800;
const long MOVEMENT_MAX_SPD_Z_DEFAULT = 800;
const long MOVEMENT_MAX_SPD_X_DEFAULT = 800;
const long MOVEMENT_MAX_SPD_Y_DEFAULT = 800;
const long MOVEMENT_MAX_SPD_Z_DEFAULT = 800;
// Use encoder (0 or 1)
const long ENCODER_ENABLED_X_DEFAULT = 0;
const long ENCODER_ENABLED_Y_DEFAULT = 0;
const long ENCODER_ENABLED_Z_DEFAULT = 0;
const long ENCODER_ENABLED_X_DEFAULT = 0;
const long ENCODER_ENABLED_Y_DEFAULT = 0;
const long ENCODER_ENABLED_Z_DEFAULT = 0;
// Type of enocder.
// 0 = non-differential encoder, channel A,B
// 1 = differenttial encoder, channel A, A*, B, B*
const long ENCODER_TYPE_X_DEFAULT = 0;
const long ENCODER_TYPE_Y_DEFAULT = 0;
const long ENCODER_TYPE_Z_DEFAULT = 0;
const long ENCODER_TYPE_X_DEFAULT = 0;
const long ENCODER_TYPE_Y_DEFAULT = 0;
const long ENCODER_TYPE_Z_DEFAULT = 0;
// Position = encoder position * scaling / 100
const long ENCODER_SCALING_X_DEFAULT = 100;
const long ENCODER_SCALING_Y_DEFAULT = 100;
const long ENCODER_SCALING_Z_DEFAULT = 100;
const long ENCODER_SCALING_X_DEFAULT = 100;
const long ENCODER_SCALING_Y_DEFAULT = 100;
const long ENCODER_SCALING_Z_DEFAULT = 100;
// Number of stes missed before motor is seen as not moving
const long ENCODER_MISSED_STEPS_MAX_X_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_MAX_Y_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_MAX_Z_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_MAX_X_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_MAX_Y_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_MAX_Z_DEFAULT = 10;
// How much a good step is substracted from the missed step total (1-99)
const long ENCODER_MISSED_STEPS_DECAY_X_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_X_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT = 10;
const long ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT = 10;
// pin guard default settings
const long PIN_GUARD_1_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_1_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_1_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_1_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_1_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_1_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_2_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_2_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_2_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_2_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_2_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_2_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_3_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_3_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_3_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_3_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_3_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_3_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_4_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_4_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_4_ACTIVE_STATE_DEFAULT = 1;
const long PIN_GUARD_4_PIN_NR_DEFAULT = 0;
const long PIN_GUARD_4_TIME_OUT_DEFAULT = 60;
const long PIN_GUARD_4_ACTIVE_STATE_DEFAULT = 1;
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 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 long STATUS_GENERAL_DEFAULT = 0;
const char SOFTWARE_VERSION[] = "GENESIS.V.01.08.EXPERIMENTAL\0";

View File

@ -7,7 +7,7 @@
#include "CurrentState.h"
static CurrentState* instance;
static CurrentState *instance;
long x = 0;
long y = 0;
long z = 0;
@ -15,120 +15,138 @@ unsigned int speed = 0;
bool endStopState[3][2];
long Q = 0;
CurrentState * CurrentState::getInstance() {
if (!instance) {
instance = new CurrentState();
};
return instance;
CurrentState *CurrentState::getInstance()
{
if (!instance)
{
instance = new CurrentState();
};
return instance;
};
CurrentState::CurrentState() {
x = 0;
y = 0;
z = 0;
speed = 0;
Q = 0;
CurrentState::CurrentState()
{
x = 0;
y = 0;
z = 0;
speed = 0;
Q = 0;
}
long CurrentState::getX() {
return x;
long CurrentState::getX()
{
return x;
}
long CurrentState::getY() {
return y;
long CurrentState::getY()
{
return y;
}
long CurrentState::getZ() {
return z;
long CurrentState::getZ()
{
return z;
}
long* CurrentState::getPoint() {
static long currentPoint[3] = {x, y, z};
return currentPoint;
long *CurrentState::getPoint()
{
static long currentPoint[3] = {x, y, z};
return currentPoint;
}
void CurrentState::setX(long newX) {
x = newX;
void CurrentState::setX(long newX)
{
x = newX;
}
void CurrentState::setY(long newY) {
y = newY;
void CurrentState::setY(long newY)
{
y = newY;
}
void CurrentState::setZ(long newZ) {
z = newZ;
void CurrentState::setZ(long newZ)
{
z = newZ;
}
void CurrentState::setEndStopState(unsigned int axis, unsigned int position, bool state) {
endStopState[axis][position] = state;
void CurrentState::setEndStopState(unsigned int axis, unsigned int position, bool state)
{
endStopState[axis][position] = state;
}
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));
CurrentState::getInstance()->setEndStopState(1,1,digitalRead(Y_MAX_PIN));
CurrentState::getInstance()->setEndStopState(2,0,digitalRead(Z_MIN_PIN));
CurrentState::getInstance()->setEndStopState(2,1,digitalRead(Z_MAX_PIN));
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));
CurrentState::getInstance()->setEndStopState(1, 1, digitalRead(Y_MAX_PIN));
CurrentState::getInstance()->setEndStopState(2, 0, digitalRead(Z_MIN_PIN));
CurrentState::getInstance()->setEndStopState(2, 1, digitalRead(Z_MAX_PIN));
}
void CurrentState::printPosition() {
Serial.print("R82");
Serial.print(" X");
Serial.print(x);
Serial.print(" Y");
Serial.print(y);
Serial.print(" Z");
Serial.print(z);
// Serial.print("\r\n");
printQAndNewLine();
void CurrentState::printPosition()
{
Serial.print("R82");
Serial.print(" X");
Serial.print(x);
Serial.print(" Y");
Serial.print(y);
Serial.print(" Z");
Serial.print(z);
// Serial.print("\r\n");
printQAndNewLine();
}
void CurrentState::printBool(bool value)
{
if (value)
{
Serial.print("1");
}
else
{
Serial.print("0");
}
if (value)
{
Serial.print("1");
}
else
{
Serial.print("0");
}
}
void CurrentState::printEndStops() {
Serial.print("R81");
Serial.print(" XA");
printBool(endStopState[0][0]);
Serial.print(" XB");
printBool(endStopState[0][1]);
Serial.print(" YA");
printBool(endStopState[1][0]);
Serial.print(" YB");
printBool(endStopState[1][1]);
Serial.print(" ZA");
printBool(endStopState[2][0]);
Serial.print(" ZB");
printBool(endStopState[2][1]);
//Serial.print("\r\n");
printQAndNewLine();
void CurrentState::printEndStops()
{
Serial.print("R81");
Serial.print(" XA");
printBool(endStopState[0][0]);
Serial.print(" XB");
printBool(endStopState[0][1]);
Serial.print(" YA");
printBool(endStopState[1][0]);
Serial.print(" YB");
printBool(endStopState[1][1]);
Serial.print(" ZA");
printBool(endStopState[2][0]);
Serial.print(" ZB");
printBool(endStopState[2][1]);
//Serial.print("\r\n");
printQAndNewLine();
}
void CurrentState::print() {
printPosition();
printEndStops();
void CurrentState::print()
{
printPosition();
printEndStops();
}
void CurrentState::setQ(long q) {
Q = q;
void CurrentState::setQ(long q)
{
Q = q;
}
void CurrentState::resetQ() {
Q = 0;
void CurrentState::resetQ()
{
Q = 0;
}
void CurrentState::printQAndNewLine() {
Serial.print(" Q");
Serial.print(Q);
Serial.print("\r\n");
void CurrentState::printQAndNewLine()
{
Serial.print(" Q");
Serial.print(Q);
Serial.print("\r\n");
}

View File

@ -10,32 +10,32 @@
#include "Arduino.h"
#include "pins.h"
class CurrentState {
class CurrentState
{
public:
static CurrentState* getInstance();
long getX();
long getY();
long getZ();
long* getPoint();
void setX(long);
void setY(long);
void setZ(long);
void setEndStopState(unsigned int, unsigned int, bool);
void printPosition();
void storeEndStops();
void printEndStops();
void print();
void printBool(bool);
static CurrentState *getInstance();
long getX();
long getY();
long getZ();
long *getPoint();
void setX(long);
void setY(long);
void setZ(long);
void setEndStopState(unsigned int, unsigned int, bool);
void printPosition();
void storeEndStops();
void printEndStops();
void print();
void printBool(bool);
void setQ(long);
void resetQ();
void printQAndNewLine();
void setQ(long);
void resetQ();
void printQAndNewLine();
private:
CurrentState();
CurrentState(CurrentState const&);
void operator=(CurrentState const&);
CurrentState();
CurrentState(CurrentState const &);
void operator=(CurrentState const &);
};
#endif /* CURRENTSTATE_H_ */

View File

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

View File

@ -14,17 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class F11Handler : public GCodeHandler {
class F11Handler : public GCodeHandler
{
public:
static F11Handler* getInstance();
int execute(Command*);
static F11Handler *getInstance();
int execute(Command *);
private:
F11Handler();
F11Handler(F11Handler const&);
void operator=(F11Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F11Handler();
F11Handler(F11Handler const &);
void operator=(F11Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F11HANDLER_H_ */

View File

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

View File

@ -14,17 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class F12Handler : public GCodeHandler {
class F12Handler : public GCodeHandler
{
public:
static F12Handler* getInstance();
int execute(Command*);
static F12Handler *getInstance();
int execute(Command *);
private:
F12Handler();
F12Handler(F12Handler const&);
void operator=(F12Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F12Handler();
F12Handler(F12Handler const &);
void operator=(F12Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F12HANDLER_H_ */

View File

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

View File

@ -14,17 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class F13Handler : public GCodeHandler {
class F13Handler : public GCodeHandler
{
public:
static F13Handler* getInstance();
int execute(Command*);
static F13Handler *getInstance();
int execute(Command *);
private:
F13Handler();
F13Handler(F13Handler const&);
void operator=(F13Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F13Handler();
F13Handler(F13Handler const &);
void operator=(F13Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F13HANDLER_H_ */

View File

@ -8,41 +8,43 @@
#include "F14Handler.h"
static F14Handler *instance;
static F14Handler* instance;
F14Handler *F14Handler::getInstance()
{
if (!instance)
{
instance = new F14Handler();
};
return 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;
int ret = 0;
if (LOGGING) {
Serial.print("R99 CALIBRATE X\r\n");
}
if (LOGGING)
{
Serial.print("R99 CALIBRATE X\r\n");
}
ret = StepperControl::getInstance()->calibrateAxis(0);
ret = StepperControl::getInstance()->calibrateAxis(0);
/*
/*
if (ret == 0) {
StepperControl::getInstance()->moveToCoords(0,0,0, 0,0,0, true, false, false);
}
*/
if (LOGGING) {
CurrentState::getInstance()->print();
}
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
return 0;
}

View File

@ -15,18 +15,18 @@
#include "Config.h"
#include "StepperControl.h"
class F14Handler : public GCodeHandler {
class F14Handler : public GCodeHandler
{
public:
static F14Handler* getInstance();
int execute(Command*);
static F14Handler *getInstance();
int execute(Command *);
private:
F14Handler();
F14Handler(F14Handler const&);
void operator=(F14Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F14Handler();
F14Handler(F14Handler const &);
void operator=(F14Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F14HANDLER_H_ */

View File

@ -8,31 +8,35 @@
#include "F15Handler.h"
static F15Handler *instance;
static F15Handler* instance;
F15Handler *F15Handler::getInstance()
{
if (!instance)
{
instance = new F15Handler();
};
return 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) {
Serial.print("R99 HOME Z\r\n");
}
if (LOGGING)
{
Serial.print("R99 HOME Z\r\n");
}
StepperControl::getInstance()->calibrateAxis(1);
StepperControl::getInstance()->calibrateAxis(1);
if (LOGGING) {
CurrentState::getInstance()->print();
}
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
return 0;
}

View File

@ -15,18 +15,18 @@
#include "Config.h"
#include "StepperControl.h"
class F15Handler : public GCodeHandler {
class F15Handler : public GCodeHandler
{
public:
static F15Handler* getInstance();
int execute(Command*);
static F15Handler *getInstance();
int execute(Command *);
private:
F15Handler();
F15Handler(F15Handler const&);
void operator=(F15Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F15Handler();
F15Handler(F15Handler const &);
void operator=(F15Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F15HANDLER_H_ */

View File

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

View File

@ -15,18 +15,18 @@
#include "Config.h"
#include "StepperControl.h"
class F16Handler : public GCodeHandler {
class F16Handler : public GCodeHandler
{
public:
static F16Handler* getInstance();
int execute(Command*);
static F16Handler *getInstance();
int execute(Command *);
private:
F16Handler();
F16Handler(F16Handler const&);
void operator=(F16Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F16Handler();
F16Handler(F16Handler const &);
void operator=(F16Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F16HANDLER_H_ */

View File

@ -7,23 +7,25 @@
#include "F20Handler.h"
static F20Handler *instance;
static F20Handler* instance;
F20Handler *F20Handler::getInstance()
{
if (!instance)
{
instance = new F20Handler();
};
return 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();
ParameterList::getInstance()->readAllValues();
return 1;
return 1;
}

View File

@ -14,16 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class F20Handler : public GCodeHandler {
class F20Handler : public GCodeHandler
{
public:
static F20Handler* getInstance();
int execute(Command*);
static F20Handler *getInstance();
int execute(Command *);
private:
F20Handler();
F20Handler(F20Handler const&);
void operator=(F20Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F20Handler();
F20Handler(F20Handler const &);
void operator=(F20Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F20HANDLER_H_ */

View File

@ -7,23 +7,25 @@
#include "F21Handler.h"
static F21Handler *instance;
static F21Handler* instance;
F21Handler *F21Handler::getInstance()
{
if (!instance)
{
instance = new F21Handler();
};
return 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());
ParameterList::getInstance()->readValue(command->getP());
return 0;
return 0;
}

View File

@ -15,16 +15,18 @@
#include "StepperControl.h"
#include "ParameterList.h"
class F21Handler : public GCodeHandler {
class F21Handler : public GCodeHandler
{
public:
static F21Handler* getInstance();
int execute(Command*);
static F21Handler *getInstance();
int execute(Command *);
private:
F21Handler();
F21Handler(F21Handler const&);
void operator=(F21Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F21Handler();
F21Handler(F21Handler const &);
void operator=(F21Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F21HANDLER_H_ */

View File

@ -7,23 +7,25 @@
#include "F22Handler.h"
static F22Handler *instance;
static F22Handler* instance;
F22Handler *F22Handler::getInstance()
{
if (!instance)
{
instance = new F22Handler();
};
return 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");
Serial.print(" ");
Serial.print("write value");
@ -42,7 +44,7 @@ Serial.print(" ");
Serial.print("\r\n");
*/
ParameterList::getInstance()->writeValue(command->getP(), command->getV());
ParameterList::getInstance()->writeValue(command->getP(), command->getV());
return 0;
return 0;
}

View File

@ -15,16 +15,18 @@
#include "StepperControl.h"
#include "ParameterList.h"
class F22Handler : public GCodeHandler {
class F22Handler : public GCodeHandler
{
public:
static F22Handler* getInstance();
int execute(Command*);
static F22Handler *getInstance();
int execute(Command *);
private:
F22Handler();
F22Handler(F22Handler const&);
void operator=(F22Handler const&);
//long adjustStepAmount(long);
//long getNumberOfSteps(double, double);
F22Handler();
F22Handler(F22Handler const &);
void operator=(F22Handler const &);
//long adjustStepAmount(long);
//long getNumberOfSteps(double, double);
};
#endif /* F22HANDLER_H_ */

View File

@ -8,25 +8,25 @@
#include "F31Handler.h"
static F31Handler *instance;
static F31Handler* instance;
F31Handler *F31Handler::getInstance()
{
if (!instance)
{
instance = new F31Handler();
};
return 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());
StatusList::getInstance()->readValue(command->getP());
return 0;
return 0;
}

View File

@ -16,19 +16,18 @@
#include "StepperControl.h"
#include "StatusList.h"
class F31Handler : public GCodeHandler {
class F31Handler : public GCodeHandler
{
public:
static F31Handler* getInstance();
int execute(Command*);
static F31Handler *getInstance();
int execute(Command *);
private:
F31Handler();
F31Handler(F31Handler const&);
void operator=(F31Handler const&);
//long adjustStepAmount(long);
//long getNumberOfSteps(double, double);
F31Handler();
F31Handler(F31Handler const &);
void operator=(F31Handler const &);
//long adjustStepAmount(long);
//long getNumberOfSteps(double, double);
};
#endif /* F31HANDLER_H_ */

View File

@ -8,25 +8,25 @@
#include "F32Handler.h"
static F32Handler *instance;
static F32Handler* instance;
F32Handler *F32Handler::getInstance()
{
if (!instance)
{
instance = new F32Handler();
};
return 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());
StatusList::getInstance()->readValue(command->getP());
return 0;
return 0;
}

View File

@ -16,19 +16,18 @@
#include "StepperControl.h"
#include "StatusList.h"
class F32Handler : public GCodeHandler {
class F32Handler : public GCodeHandler
{
public:
static F32Handler* getInstance();
int execute(Command*);
static F32Handler *getInstance();
int execute(Command *);
private:
F32Handler();
F32Handler(F32Handler const&);
void operator=(F32Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F32Handler();
F32Handler(F32Handler const &);
void operator=(F32Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F32HANDLER_H_ */

View File

@ -9,23 +9,25 @@
#include "F41Handler.h"
static F41Handler *instance;
static F41Handler* instance;
F41Handler *F41Handler::getInstance()
{
if (!instance)
{
instance = new F41Handler();
};
return 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());
PinControl::getInstance()->writeValue(command->getP(), command->getV(), command->getM());
return 0;
return 0;
}

View File

@ -14,20 +14,16 @@
#include "Config.h"
#include "PinControl.h"
class F41Handler : public GCodeHandler {
class F41Handler : public GCodeHandler
{
public:
static F41Handler* getInstance();
int execute(Command*);
static F41Handler *getInstance();
int execute(Command *);
private:
F41Handler();
F41Handler(F41Handler const&);
void operator=(F41Handler const&);
F41Handler();
F41Handler(F41Handler const &);
void operator=(F41Handler const &);
};
#endif /* F41HANDLER_H_ */

View File

@ -7,23 +7,25 @@
#include "F42Handler.h"
static F42Handler *instance;
static F42Handler* instance;
F42Handler *F42Handler::getInstance()
{
if (!instance)
{
instance = new F42Handler();
};
return 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());
PinControl::getInstance()->readValue(command->getP(), command->getM());
return 0;
return 0;
}

View File

@ -14,20 +14,16 @@
#include "Config.h"
#include "PinControl.h"
class F42Handler : public GCodeHandler {
class F42Handler : public GCodeHandler
{
public:
static F42Handler* getInstance();
int execute(Command*);
static F42Handler *getInstance();
int execute(Command *);
private:
F42Handler();
F42Handler(F42Handler const&);
void operator=(F42Handler const&);
F42Handler();
F42Handler(F42Handler const &);
void operator=(F42Handler const &);
};
#endif /* F42HANDLER_H_ */

View File

@ -9,30 +9,25 @@
#include "F43Handler.h"
static F43Handler *instance;
static F43Handler* instance;
F43Handler *F43Handler::getInstance()
{
if (!instance)
{
instance = new F43Handler();
};
return 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());
PinControl::getInstance()->setMode(command->getP(), command->getM());
return 0;
return 0;
}

View File

@ -14,14 +14,16 @@
#include "Config.h"
#include "PinControl.h"
class F43Handler : public GCodeHandler {
class F43Handler : public GCodeHandler
{
public:
static F43Handler* getInstance();
int execute(Command*);
static F43Handler *getInstance();
int execute(Command *);
private:
F43Handler();
F43Handler(F43Handler const&);
void operator=(F43Handler const&);
F43Handler();
F43Handler(F43Handler const &);
void operator=(F43Handler const &);
};
#endif /* F43HANDLER_H_ */

View File

@ -9,23 +9,25 @@
#include "F44Handler.h"
static F44Handler *instance;
static F44Handler* instance;
F44Handler *F44Handler::getInstance()
{
if (!instance)
{
instance = new F44Handler();
};
return 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());
PinControl::getInstance()->writePulse(command->getP(), command->getV(), command->getW(), command->getT(), command->getM());
return 0;
return 0;
}

View File

@ -14,17 +14,16 @@
#include "Config.h"
#include "PinControl.h"
class F44Handler : public GCodeHandler {
class F44Handler : public GCodeHandler
{
public:
static F44Handler* getInstance();
int execute(Command*);
static F44Handler *getInstance();
int execute(Command *);
private:
F44Handler();
F44Handler(F44Handler const&);
void operator=(F44Handler const&);
F44Handler();
F44Handler(F44Handler const &);
void operator=(F44Handler const &);
};
#endif /* F44HANDLER_H_ */

View File

@ -9,23 +9,25 @@
#include "F61Handler.h"
static F61Handler *instance;
static F61Handler* instance;
F61Handler *F61Handler::getInstance()
{
if (!instance)
{
instance = new F61Handler();
};
return 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());
ServoControl::getInstance()->setAngle(command->getP(), command->getV());
return 0;
return 0;
}

View File

@ -14,20 +14,16 @@
#include "Config.h"
#include "ServoControl.h"
class F61Handler : public GCodeHandler {
class F61Handler : public GCodeHandler
{
public:
static F61Handler* getInstance();
int execute(Command*);
static F61Handler *getInstance();
int execute(Command *);
private:
F61Handler();
F61Handler(F61Handler const&);
void operator=(F61Handler const&);
F61Handler();
F61Handler(F61Handler const &);
void operator=(F61Handler const &);
};
#endif /* F61HANDLER_H_ */

View File

@ -9,40 +9,40 @@
#include "F81Handler.h"
static F81Handler *instance;
static F81Handler* instance;
F81Handler *F81Handler::getInstance()
{
if (!instance)
{
instance = new F81Handler();
};
return 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");
Serial.print("home\r\n");
if (LOGGING) {
Serial.print("R99 Report end stops\r\n");
}
if (LOGGING)
{
Serial.print("R99 Report end stops\r\n");
}
// Report back the end stops
CurrentState::getInstance()->storeEndStops();
CurrentState::getInstance()->printEndStops();
// Report back the end stops
CurrentState::getInstance()->storeEndStops();
CurrentState::getInstance()->printEndStops();
// Also report back some selected pin numbers: 8, 9, 10, 13
PinControl::getInstance()->readValue( 8, 0);
PinControl::getInstance()->readValue( 9, 0);
PinControl::getInstance()->readValue(10, 0);
PinControl::getInstance()->readValue(13, 0);
// Also report back some selected pin numbers: 8, 9, 10, 13
PinControl::getInstance()->readValue(8, 0);
PinControl::getInstance()->readValue(9, 0);
PinControl::getInstance()->readValue(10, 0);
PinControl::getInstance()->readValue(13, 0);
return 0;
return 0;
}

View File

@ -15,17 +15,18 @@
#include "StepperControl.h"
#include "PinControl.h"
class F81Handler : public GCodeHandler {
class F81Handler : public GCodeHandler
{
public:
static F81Handler* getInstance();
int execute(Command*);
static F81Handler *getInstance();
int execute(Command *);
private:
F81Handler();
F81Handler(F81Handler const&);
void operator=(F81Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F81Handler();
F81Handler(F81Handler const &);
void operator=(F81Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F81HANDLER_H_ */

View File

@ -9,30 +9,30 @@
#include "F82Handler.h"
static F82Handler *instance;
static F82Handler* instance;
F82Handler *F82Handler::getInstance()
{
if (!instance)
{
instance = new F82Handler();
};
return 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) {
Serial.print("R99 Report current position\r\n");
}
if (LOGGING)
{
Serial.print("R99 Report current position\r\n");
}
CurrentState::getInstance()->printPosition();
CurrentState::getInstance()->printPosition();
return 0;
return 0;
}

View File

@ -14,17 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class F82Handler : public GCodeHandler {
class F82Handler : public GCodeHandler
{
public:
static F82Handler* getInstance();
int execute(Command*);
static F82Handler *getInstance();
int execute(Command *);
private:
F82Handler();
F82Handler(F82Handler const&);
void operator=(F82Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F82Handler();
F82Handler(F82Handler const &);
void operator=(F82Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F82HANDLER_H_ */

View File

@ -9,33 +9,33 @@
#include "F83Handler.h"
static F83Handler *instance;
static F83Handler* instance;
F83Handler *F83Handler::getInstance()
{
if (!instance)
{
instance = new F83Handler();
};
return 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) {
Serial.print("R99 Report server version\r\n");
}
if (LOGGING)
{
Serial.print("R99 Report server version\r\n");
}
Serial.print("R83 ");
Serial.print(SOFTWARE_VERSION);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
Serial.print("R83 ");
Serial.print(SOFTWARE_VERSION);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
return 0;
return 0;
}

View File

@ -14,17 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class F83Handler : public GCodeHandler {
class F83Handler : public GCodeHandler
{
public:
static F83Handler* getInstance();
int execute(Command*);
static F83Handler *getInstance();
int execute(Command *);
private:
F83Handler();
F83Handler(F83Handler const&);
void operator=(F83Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
F83Handler();
F83Handler(F83Handler const &);
void operator=(F83Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* F83HANDLER_H_ */

View File

@ -7,51 +7,49 @@
#include "G00Handler.h"
static G00Handler *instance;
static G00Handler* instance;
G00Handler *G00Handler::getInstance()
{
if (!instance)
{
instance = new G00Handler();
};
return 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("G00 was here\r\n");
// Serial.print("R99");
// Serial.print(" X ");
// Serial.print(command->getX());
// Serial.print(" Y ");
// Serial.print(command->getY());
// Serial.print(" Z ");
// Serial.print(command->getZ());
// Serial.print(" A ");
// Serial.print(command->getA());
// Serial.print(" B ");
// Serial.print(command->getB());
// Serial.print(" C ");
// Serial.print(command->getC());
// Serial.print("\r\n");
StepperControl::getInstance()->moveToCoords(
command->getX(), command->getY(), command->getZ(),
command->getA(), command->getB(), command->getC(),
false, false, false);
// Serial.print("R99");
// Serial.print(" X ");
// Serial.print(command->getX());
// Serial.print(" Y ");
// Serial.print(command->getY());
// Serial.print(" Z ");
// Serial.print(command->getZ());
// Serial.print(" A ");
// Serial.print(command->getA());
// Serial.print(" B ");
// Serial.print(command->getB());
// Serial.print(" C ");
// Serial.print(command->getC());
// Serial.print("\r\n");
StepperControl::getInstance()->moveToCoords
(
command->getX(), command->getY(), command->getZ(),
command->getA(), command->getB(), command->getC(),
false, false, false
);
if (LOGGING) {
CurrentState::getInstance()->print();
}
return 0;
if (LOGGING)
{
CurrentState::getInstance()->print();
}
return 0;
}

View File

@ -14,16 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class G00Handler : public GCodeHandler {
class G00Handler : public GCodeHandler
{
public:
static G00Handler* getInstance();
int execute(Command*);
static G00Handler *getInstance();
int execute(Command *);
private:
G00Handler();
G00Handler(G00Handler const&);
void operator=(G00Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
G00Handler();
G00Handler(G00Handler const &);
void operator=(G00Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* G00HANDLER_H_ */

View File

@ -7,29 +7,32 @@
#include "G28Handler.h"
static G28Handler *instance;
static G28Handler* instance;
G28Handler *G28Handler::getInstance()
{
if (!instance)
{
instance = new G28Handler();
};
return 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");
//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) {
CurrentState::getInstance()->print();
}
return 0;
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)
{
CurrentState::getInstance()->print();
}
return 0;
}

View File

@ -14,16 +14,18 @@
#include "Config.h"
#include "StepperControl.h"
class G28Handler : public GCodeHandler {
class G28Handler : public GCodeHandler
{
public:
static G28Handler* getInstance();
int execute(Command*);
static G28Handler *getInstance();
int execute(Command *);
private:
G28Handler();
G28Handler(G28Handler const&);
void operator=(G28Handler const&);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
G28Handler();
G28Handler(G28Handler const &);
void operator=(G28Handler const &);
long adjustStepAmount(long);
long getNumberOfSteps(double, double);
};
#endif /* G28HANDLER_H_ */

View File

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

View File

@ -9,11 +9,12 @@
#define GCODEHANDLER_H_
#include "Command.h"
class GCodeHandler {
class GCodeHandler
{
public:
GCodeHandler();
virtual ~GCodeHandler();
virtual int execute(Command*);
GCodeHandler();
virtual ~GCodeHandler();
virtual int execute(Command *);
};
#endif /* GCODEHANDLER_H_ */

View File

@ -9,31 +9,33 @@
#include "GCodeProcessor.h"
#include "CurrentState.h"
GCodeProcessor::GCodeProcessor() {
GCodeProcessor::GCodeProcessor()
{
}
GCodeProcessor::~GCodeProcessor() {
GCodeProcessor::~GCodeProcessor()
{
}
void GCodeProcessor::printCommandLog(Command* command) {
Serial.print("command == NULL: ");
Serial.println("\r\n");
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;
int execution = 0;
long Q = command->getQ();
CurrentState::getInstance()->setQ(Q);
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
// 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
// Tim 2017-04-15 Disable until the raspberry code is ready
/*
// Tim 2017-04-15 Disable until the raspberry code is ready
/*
if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
if ( command->getCodeEnum() == G00 ||
command->getCodeEnum() == G01 ||
@ -51,90 +53,155 @@ int GCodeProcessor::execute(Command* command) {
}
*/
// Return error when no command or invalid command is found
// Return error when no command or invalid command is found
if(command == NULL) {
if(LOGGING) {
printCommandLog(command);
}
return -1;
}
if (command == NULL)
{
if (LOGGING)
{
printCommandLog(command);
}
return -1;
}
if(command->getCodeEnum() == CODE_UNDEFINED) {
if(LOGGING) {
printCommandLog(command);
}
return -1;
}
if (command->getCodeEnum() == CODE_UNDEFINED)
{
if (LOGGING)
{
printCommandLog(command);
}
return -1;
}
// Get the right handler for this command
// Get the right handler for this command
GCodeHandler* handler = getGCodeHandler(command->getCodeEnum());
GCodeHandler *handler = getGCodeHandler(command->getCodeEnum());
if(handler == NULL) {
Serial.println("R99 handler == NULL\r\n");
return -1;
}
if (handler == NULL)
{
Serial.println("R99 handler == NULL\r\n");
return -1;
}
// Execute te command, report start and end
// Execute te command, report start and end
Serial.print(COMM_REPORT_CMD_START);
CurrentState::getInstance()->printQAndNewLine();
Serial.print(COMM_REPORT_CMD_START);
CurrentState::getInstance()->printQAndNewLine();
execution = handler->execute(command);
if(execution == 0) {
Serial.print(COMM_REPORT_CMD_DONE);
CurrentState::getInstance()->printQAndNewLine();
} else {
Serial.print(COMM_REPORT_CMD_ERROR);
CurrentState::getInstance()->printQAndNewLine();
}
execution = handler->execute(command);
if (execution == 0)
{
Serial.print(COMM_REPORT_CMD_DONE);
CurrentState::getInstance()->printQAndNewLine();
}
else
{
Serial.print(COMM_REPORT_CMD_ERROR);
CurrentState::getInstance()->printQAndNewLine();
}
CurrentState::getInstance()->resetQ();
return execution;
CurrentState::getInstance()->resetQ();
return execution;
};
GCodeHandler* GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum) {
GCodeHandler *GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum)
{
GCodeHandler* handler = NULL;
GCodeHandler *handler = NULL;
// These are if statements so they can be disabled as test
// Usefull when running into memory issues again
// 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 == 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 == 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 == F81) {handler = F81Handler::getInstance();}
if (codeEnum == F82) {handler = F82Handler::getInstance();}
if (codeEnum == F83) {handler = F83Handler::getInstance();}
if (codeEnum == F84) {handler = F84Handler::getInstance();}
return handler;
return handler;
}

View File

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

View File

@ -18,4 +18,4 @@ FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
SOFTWARE.

View File

@ -25,12 +25,12 @@ extern struct __freelist *__flp;
/* Calculates the size of the free list */
int freeListSize()
{
struct __freelist* current;
struct __freelist *current;
int total = 0;
for (current = __flp; current; current = current->nx)
{
total += 2; /* Add two bytes for the memory block's header */
total += (int) current->sz;
total += (int)current->sz;
}
return total;

View File

@ -2,7 +2,7 @@
// http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1213583720/15
// Extended by Matthew Murdoch to include walking of the free list.
#ifndef MEMORY_FREE_H
#ifndef MEMORY_FREE_H
#define MEMORY_FREE_H
#ifdef __cplusplus
@ -11,7 +11,7 @@ extern "C" {
int freeMemory();
#ifdef __cplusplus
#ifdef __cplusplus
}
#endif

View File

@ -1,82 +1,97 @@
#include "ParameterList.h"
#include <EEPROM.h>
static ParameterList* instanceParam;
static ParameterList *instanceParam;
int paramValues[PARAM_NR_OF_PARAMS];
ParameterList * ParameterList::getInstance() {
if (!instanceParam) {
instanceParam = new ParameterList();
};
return instanceParam;
ParameterList *ParameterList::getInstance()
{
if (!instanceParam)
{
instanceParam = new ParameterList();
};
return instanceParam;
}
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
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
int paramChangeNr = 0;
int paramChangeNr = 0;
int paramVersion = readValueEeprom(0);
if (paramVersion <= 0) {
setAllValuesToDefault();
writeAllValuesToEeprom();
} else {
//if (readValueEeprom(PARAM_USE_EEPROM) == 1) {
readAllValuesFromEeprom();
//} else {
// setAllValuesToDefault();
//}
}
int paramVersion = readValueEeprom(0);
if (paramVersion <= 0)
{
setAllValuesToDefault();
writeAllValuesToEeprom();
}
else
{
//if (readValueEeprom(PARAM_USE_EEPROM) == 1) {
readAllValuesFromEeprom();
//} else {
// setAllValuesToDefault();
//}
}
}
// ===== 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)) {
// Retrieve the value from memory
int value = paramValues[id];
// Check if the value is an existing parameter
if (validParam(id))
{
// Retrieve the value from memory
int value = paramValues[id];
// Send to the raspberrt pi
Serial.print("R21");
Serial.print(" ");
Serial.print("P");
Serial.print(id);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
// Send to the raspberrt pi
Serial.print("R21");
Serial.print(" ");
Serial.print("P");
Serial.print(id);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
}
else
{
Serial.print("R99 Error: invalid parameter id\r\n");
}
} else {
Serial.print("R99 Error: invalid parameter id\r\n");
}
return 0;
return 0;
}
int ParameterList::writeValue(int id, int value) {
int ParameterList::writeValue(int id, int value)
{
if (paramChangeNr < 9999) {
paramChangeNr++;
} else {
paramChangeNr = 0;
}
if (paramChangeNr < 9999)
{
paramChangeNr++;
}
else
{
paramChangeNr = 0;
}
// Check if the value is a valid parameter
if (validParam(id)) {
// Store the value in memory
paramValues[id] = value;
writeValueEeprom(id, value);
} else {
Serial.print("R99 Error: invalid parameter id\r\n");
}
// Check if the value is a valid parameter
if (validParam(id))
{
// Store the value in memory
paramValues[id] = value;
writeValueEeprom(id, value);
}
else
{
Serial.print("R99 Error: invalid parameter id\r\n");
}
/*
/*
// Debugging output
Serial.print("R99");
Serial.print(" ");
@ -93,264 +108,400 @@ int ParameterList::writeValue(int id, int value) {
CurrentState::getInstance()->printQAndNewLine();
*/
// If any value is written,
// trigger the loading of the new configuration in all other modules
sendConfigToModules();
// If any value is written,
// trigger the loading of the new configuration in all other modules
sendConfigToModules();
return 0;
return 0;
}
void ParameterList::sendConfigToModules() {
// Trigger other modules to load the new values
PinGuard::getInstance()->loadConfig();
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)) {
readValue(i);
}
}
// 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))
{
readValue(i);
}
}
}
int ParameterList::getValue(int id) {
return paramValues[id];
int ParameterList::getValue(int id)
{
return paramValues[id];
}
int ParameterList::paramChangeNumber() {
return paramChangeNr;
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;
// Assume all values are ints and calculate address for that
int address = id * 2;
//Read the 2 bytes from the eeprom memory.
long two = EEPROM.read(address);
long one = EEPROM.read(address + 1);
//Read the 2 bytes from the eeprom memory.
long two = EEPROM.read(address);
long one = EEPROM.read(address + 1);
//Return the recomposed long by using bitshift.
return ((two << 0) & 0xFF) + ((one << 8) & 0xFFFF);
//Return the recomposed long by using bitshift.
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;
// Assume all values are ints and calculate address for that
int address = id * 2;
//Decomposition from a int to 2 bytes by using bitshift.
//One = Most significant -> Two = Least significant byte
byte two = (value & 0xFF);
byte one = ((value >> 8) & 0xFF);
//Decomposition from a int to 2 bytes by using bitshift.
//One = Most significant -> Two = Least significant byte
byte two = (value & 0xFF);
byte one = ((value >> 8) & 0xFF);
//Write the 4 bytes into the eeprom memory.
EEPROM.write(address , two);
EEPROM.write(address + 1, one);
//Write the 4 bytes into the eeprom memory.
EEPROM.write(address, two);
EEPROM.write(address + 1, one);
return 0;
return 0;
}
int ParameterList::readAllValuesFromEeprom() {
// Write all existing values to eeprom
for (int i=0; i < PARAM_NR_OF_PARAMS; i++) {
if (validParam(i)) {
paramValues[i] = readValueEeprom(i);
if (paramValues[i] == -1) {
// When parameters are still on default,
// load a good value and save it
loadDefaultValue(i);
writeValueEeprom(i,paramValues[i]);
}
}
}
int ParameterList::readAllValuesFromEeprom()
{
// Write all existing values to eeprom
for (int i = 0; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i))
{
paramValues[i] = readValueEeprom(i);
if (paramValues[i] == -1)
{
// When parameters are still on default,
// load a good value and save it
loadDefaultValue(i);
writeValueEeprom(i, paramValues[i]);
}
}
}
}
int ParameterList::writeAllValuesToEeprom() {
// Write all existing values to eeprom
for (int i=0; i < 150; i++)
{
if (validParam(i)) {
writeValueEeprom(i,paramValues[i]);
}
}
int ParameterList::writeAllValuesToEeprom()
{
// Write all existing values to eeprom
for (int i = 0; i < 150; i++)
{
if (validParam(i))
{
writeValueEeprom(i, paramValues[i]);
}
}
}
// ==== parameter valdation and defaults
int ParameterList::setAllValuesToDefault() {
// Copy default values to the memory values
for (int i=0; i < PARAM_NR_OF_PARAMS; i++)
{
if (validParam(i)) {
loadDefaultValue(i);
}
}
int ParameterList::setAllValuesToDefault()
{
// Copy default values to the memory values
for (int i = 0; i < PARAM_NR_OF_PARAMS; 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;
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 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)
{
case PARAM_VERSION:
case PARAM_CONFIG_OK:
case PARAM_USE_EEPROM:
case MOVEMENT_TIMEOUT_X:
case MOVEMENT_TIMEOUT_Y:
case MOVEMENT_TIMEOUT_Z:
case MOVEMENT_ENABLE_ENDPOINTS_X:
case MOVEMENT_ENABLE_ENDPOINTS_Y:
case MOVEMENT_ENABLE_ENDPOINTS_Z:
case MOVEMENT_INVERT_ENDPOINTS_X:
case MOVEMENT_INVERT_ENDPOINTS_Y:
case MOVEMENT_INVERT_ENDPOINTS_Z:
case MOVEMENT_INVERT_MOTOR_X:
case MOVEMENT_INVERT_MOTOR_Y:
case MOVEMENT_INVERT_MOTOR_Z:
case MOVEMENT_SECONDARY_MOTOR_X:
case MOVEMENT_SECONDARY_MOTOR_INVERT_X:
case MOVEMENT_STEPS_ACC_DEC_X:
case MOVEMENT_STEPS_ACC_DEC_Y:
case MOVEMENT_STEPS_ACC_DEC_Z:
case MOVEMENT_HOME_UP_X:
case MOVEMENT_HOME_UP_Y:
case MOVEMENT_HOME_UP_Z:
case MOVEMENT_MIN_SPD_X:
case MOVEMENT_MIN_SPD_Y:
case MOVEMENT_MIN_SPD_Z:
case MOVEMENT_MAX_SPD_X:
case MOVEMENT_MAX_SPD_Y:
case MOVEMENT_MAX_SPD_Z:
case ENCODER_ENABLED_X:
case ENCODER_ENABLED_Y:
case ENCODER_ENABLED_Z:
case ENCODER_TYPE_X:
case ENCODER_TYPE_Y:
case ENCODER_TYPE_Z:
case ENCODER_MISSED_STEPS_MAX_X:
case ENCODER_MISSED_STEPS_MAX_Y:
case ENCODER_MISSED_STEPS_MAX_Z:
case ENCODER_SCALING_X:
case ENCODER_SCALING_Y:
case ENCODER_SCALING_Z:
case ENCODER_MISSED_STEPS_DECAY_X:
case ENCODER_MISSED_STEPS_DECAY_Y:
case ENCODER_MISSED_STEPS_DECAY_Z:
case PIN_GUARD_1_PIN_NR:
case PIN_GUARD_1_TIME_OUT:
case PIN_GUARD_1_ACTIVE_STATE:
case PIN_GUARD_2_PIN_NR:
case PIN_GUARD_2_TIME_OUT:
case PIN_GUARD_2_ACTIVE_STATE:
case PIN_GUARD_3_PIN_NR:
case PIN_GUARD_3_TIME_OUT:
case PIN_GUARD_3_ACTIVE_STATE:
case PIN_GUARD_4_PIN_NR:
case PIN_GUARD_4_TIME_OUT:
case PIN_GUARD_4_ACTIVE_STATE:
case PIN_GUARD_5_PIN_NR:
case PIN_GUARD_5_TIME_OUT:
case PIN_GUARD_5_ACTIVE_STATE:
return true;
default:
return false;
}
// Check if the id is a valid one
switch (id)
{
case PARAM_VERSION:
case PARAM_CONFIG_OK:
case PARAM_USE_EEPROM:
case MOVEMENT_TIMEOUT_X:
case MOVEMENT_TIMEOUT_Y:
case MOVEMENT_TIMEOUT_Z:
case MOVEMENT_ENABLE_ENDPOINTS_X:
case MOVEMENT_ENABLE_ENDPOINTS_Y:
case MOVEMENT_ENABLE_ENDPOINTS_Z:
case MOVEMENT_INVERT_ENDPOINTS_X:
case MOVEMENT_INVERT_ENDPOINTS_Y:
case MOVEMENT_INVERT_ENDPOINTS_Z:
case MOVEMENT_INVERT_MOTOR_X:
case MOVEMENT_INVERT_MOTOR_Y:
case MOVEMENT_INVERT_MOTOR_Z:
case MOVEMENT_SECONDARY_MOTOR_X:
case MOVEMENT_SECONDARY_MOTOR_INVERT_X:
case MOVEMENT_STEPS_ACC_DEC_X:
case MOVEMENT_STEPS_ACC_DEC_Y:
case MOVEMENT_STEPS_ACC_DEC_Z:
case MOVEMENT_HOME_UP_X:
case MOVEMENT_HOME_UP_Y:
case MOVEMENT_HOME_UP_Z:
case MOVEMENT_MIN_SPD_X:
case MOVEMENT_MIN_SPD_Y:
case MOVEMENT_MIN_SPD_Z:
case MOVEMENT_MAX_SPD_X:
case MOVEMENT_MAX_SPD_Y:
case MOVEMENT_MAX_SPD_Z:
case ENCODER_ENABLED_X:
case ENCODER_ENABLED_Y:
case ENCODER_ENABLED_Z:
case ENCODER_TYPE_X:
case ENCODER_TYPE_Y:
case ENCODER_TYPE_Z:
case ENCODER_MISSED_STEPS_MAX_X:
case ENCODER_MISSED_STEPS_MAX_Y:
case ENCODER_MISSED_STEPS_MAX_Z:
case ENCODER_SCALING_X:
case ENCODER_SCALING_Y:
case ENCODER_SCALING_Z:
case ENCODER_MISSED_STEPS_DECAY_X:
case ENCODER_MISSED_STEPS_DECAY_Y:
case ENCODER_MISSED_STEPS_DECAY_Z:
case PIN_GUARD_1_PIN_NR:
case PIN_GUARD_1_TIME_OUT:
case PIN_GUARD_1_ACTIVE_STATE:
case PIN_GUARD_2_PIN_NR:
case PIN_GUARD_2_TIME_OUT:
case PIN_GUARD_2_ACTIVE_STATE:
case PIN_GUARD_3_PIN_NR:
case PIN_GUARD_3_TIME_OUT:
case PIN_GUARD_3_ACTIVE_STATE:
case PIN_GUARD_4_PIN_NR:
case PIN_GUARD_4_TIME_OUT:
case PIN_GUARD_4_ACTIVE_STATE:
case PIN_GUARD_5_PIN_NR:
case PIN_GUARD_5_TIME_OUT:
case PIN_GUARD_5_ACTIVE_STATE:
return true;
default:
return false;
}
}

View File

@ -9,98 +9,96 @@
//#define NULL 0
const int PARAM_NR_OF_PARAMS = 225;
enum ParamListEnum
{
PARAM_VERSION = 0,
PARAM_TEST = 1,
PARAM_CONFIG_OK = 2,
PARAM_USE_EEPROM = 3,
PARAM_VERSION = 0,
PARAM_TEST = 1,
PARAM_CONFIG_OK = 2,
PARAM_USE_EEPROM = 3,
// stepper motor settings
// stepper motor settings
MOVEMENT_TIMEOUT_X = 11,
MOVEMENT_TIMEOUT_Y = 12,
MOVEMENT_TIMEOUT_Z = 13,
MOVEMENT_TIMEOUT_X = 11,
MOVEMENT_TIMEOUT_Y = 12,
MOVEMENT_TIMEOUT_Z = 13,
MOVEMENT_INVERT_ENDPOINTS_X = 21,
MOVEMENT_INVERT_ENDPOINTS_Y = 22,
MOVEMENT_INVERT_ENDPOINTS_Z = 23,
MOVEMENT_INVERT_ENDPOINTS_X = 21,
MOVEMENT_INVERT_ENDPOINTS_Y = 22,
MOVEMENT_INVERT_ENDPOINTS_Z = 23,
MOVEMENT_ENABLE_ENDPOINTS_X = 25,
MOVEMENT_ENABLE_ENDPOINTS_Y = 26,
MOVEMENT_ENABLE_ENDPOINTS_Z = 27,
MOVEMENT_ENABLE_ENDPOINTS_X = 25,
MOVEMENT_ENABLE_ENDPOINTS_Y = 26,
MOVEMENT_ENABLE_ENDPOINTS_Z = 27,
MOVEMENT_INVERT_MOTOR_X = 31,
MOVEMENT_INVERT_MOTOR_Y = 32,
MOVEMENT_INVERT_MOTOR_Z = 33,
MOVEMENT_INVERT_MOTOR_X = 31,
MOVEMENT_INVERT_MOTOR_Y = 32,
MOVEMENT_INVERT_MOTOR_Z = 33,
MOVEMENT_SECONDARY_MOTOR_X = 36,
MOVEMENT_SECONDARY_MOTOR_INVERT_X = 37,
MOVEMENT_SECONDARY_MOTOR_X = 36,
MOVEMENT_SECONDARY_MOTOR_INVERT_X = 37,
MOVEMENT_STEPS_ACC_DEC_X = 41,
MOVEMENT_STEPS_ACC_DEC_Y = 42,
MOVEMENT_STEPS_ACC_DEC_Z = 43,
MOVEMENT_STEPS_ACC_DEC_X = 41,
MOVEMENT_STEPS_ACC_DEC_Y = 42,
MOVEMENT_STEPS_ACC_DEC_Z = 43,
MOVEMENT_HOME_UP_X = 51,
MOVEMENT_HOME_UP_Y = 52,
MOVEMENT_HOME_UP_Z = 53,
MOVEMENT_HOME_UP_X = 51,
MOVEMENT_HOME_UP_Y = 52,
MOVEMENT_HOME_UP_Z = 53,
MOVEMENT_MIN_SPD_X = 61,
MOVEMENT_MIN_SPD_Y = 62,
MOVEMENT_MIN_SPD_Z = 63,
MOVEMENT_MIN_SPD_X = 61,
MOVEMENT_MIN_SPD_Y = 62,
MOVEMENT_MIN_SPD_Z = 63,
MOVEMENT_MAX_SPD_X = 71,
MOVEMENT_MAX_SPD_Y = 72,
MOVEMENT_MAX_SPD_Z = 73,
MOVEMENT_MAX_SPD_X = 71,
MOVEMENT_MAX_SPD_Y = 72,
MOVEMENT_MAX_SPD_Z = 73,
// encoder settings
ENCODER_ENABLED_X = 101,
ENCODER_ENABLED_Y = 102,
ENCODER_ENABLED_Z = 103,
// encoder settings
ENCODER_ENABLED_X = 101,
ENCODER_ENABLED_Y = 102,
ENCODER_ENABLED_Z = 103,
ENCODER_TYPE_X = 105,
ENCODER_TYPE_Y = 106,
ENCODER_TYPE_Z = 107,
ENCODER_TYPE_X = 105,
ENCODER_TYPE_Y = 106,
ENCODER_TYPE_Z = 107,
ENCODER_MISSED_STEPS_MAX_X = 111,
ENCODER_MISSED_STEPS_MAX_Y = 112,
ENCODER_MISSED_STEPS_MAX_Z = 113,
ENCODER_MISSED_STEPS_MAX_X = 111,
ENCODER_MISSED_STEPS_MAX_Y = 112,
ENCODER_MISSED_STEPS_MAX_Z = 113,
ENCODER_SCALING_X = 115,
ENCODER_SCALING_Y = 116,
ENCODER_SCALING_Z = 117,
ENCODER_SCALING_X = 115,
ENCODER_SCALING_Y = 116,
ENCODER_SCALING_Z = 117,
ENCODER_MISSED_STEPS_DECAY_X = 121,
ENCODER_MISSED_STEPS_DECAY_Y = 122,
ENCODER_MISSED_STEPS_DECAY_Z = 123,
ENCODER_MISSED_STEPS_DECAY_X = 121,
ENCODER_MISSED_STEPS_DECAY_Y = 122,
ENCODER_MISSED_STEPS_DECAY_Z = 123,
// not used in software at this time
MOVEMENT_AXIS_NR_STEPS_X = 141,
MOVEMENT_AXIS_NR_STEPS_Y = 142,
MOVEMENT_AXIS_NR_STEPS_Z = 143,
// not used in software at this time
MOVEMENT_AXIS_NR_STEPS_X = 141,
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,
PIN_GUARD_1_ACTIVE_STATE = 203,
// pin guard settings
PIN_GUARD_1_PIN_NR = 201,
PIN_GUARD_1_TIME_OUT = 202,
PIN_GUARD_1_ACTIVE_STATE = 203,
PIN_GUARD_2_PIN_NR = 205,
PIN_GUARD_2_TIME_OUT = 206,
PIN_GUARD_2_ACTIVE_STATE = 207,
PIN_GUARD_2_PIN_NR = 205,
PIN_GUARD_2_TIME_OUT = 206,
PIN_GUARD_2_ACTIVE_STATE = 207,
PIN_GUARD_3_PIN_NR = 211,
PIN_GUARD_3_TIME_OUT = 212,
PIN_GUARD_3_ACTIVE_STATE = 213,
PIN_GUARD_3_PIN_NR = 211,
PIN_GUARD_3_TIME_OUT = 212,
PIN_GUARD_3_ACTIVE_STATE = 213,
PIN_GUARD_4_PIN_NR = 215,
PIN_GUARD_4_TIME_OUT = 216,
PIN_GUARD_4_ACTIVE_STATE = 217,
PIN_GUARD_4_PIN_NR = 215,
PIN_GUARD_4_TIME_OUT = 216,
PIN_GUARD_4_ACTIVE_STATE = 217,
PIN_GUARD_5_PIN_NR = 221,
PIN_GUARD_5_TIME_OUT = 222,
PIN_GUARD_5_ACTIVE_STATE = 223
PIN_GUARD_5_PIN_NR = 221,
PIN_GUARD_5_TIME_OUT = 222,
PIN_GUARD_5_ACTIVE_STATE = 223
};
@ -108,37 +106,37 @@ enum ParamListEnum
#define NULL 0
*/
class ParameterList {
ParamListEnum paramListEnum;
class ParameterList
{
ParamListEnum paramListEnum;
public:
static ParameterList* getInstance();
int writeValue(int id, int value);
int readValue(int id);
int getValue(int id);
static ParameterList *getInstance();
int writeValue(int id, int value);
int readValue(int id);
int getValue(int id);
bool validParam(int id);
void loadDefaultValue(int id);
bool validParam(int id);
void loadDefaultValue(int id);
int readAllValues();
int readAllValuesFromEeprom();
int writeAllValuesToEeprom();
int setAllValuesToDefault();
int readAllValues();
int readAllValuesFromEeprom();
int writeAllValuesToEeprom();
int setAllValuesToDefault();
int readValueEeprom(int id);
int writeValueEeprom(int id, int value);
int readValueEeprom(int id);
int writeValueEeprom(int id, int value);
void sendConfigToModules();
void sendConfigToModules();
int paramChangeNumber();
int paramChangeNumber();
private:
ParameterList();
ParameterList(ParameterList const&);
void operator=(ParameterList const&);
int paramChangeNr;
ParameterList();
ParameterList(ParameterList const &);
void operator=(ParameterList const &);
int paramChangeNr;
};
#endif /* PARAMETERLIST_H_ */

View File

@ -1,71 +1,84 @@
#include "PinControl.h"
static PinControl* instance;
static PinControl *instance;
PinControl * PinControl::getInstance() {
if (!instance) {
instance = new PinControl();
};
return instance;
}
;
PinControl *PinControl::getInstance()
{
if (!instance)
{
instance = new PinControl();
};
return instance;
};
PinControl::PinControl() {
PinControl::PinControl()
{
}
int PinControl::setMode(int pinNr, int mode) {
pinMode(pinNr , mode );
return 0;
int PinControl::setMode(int pinNr, int mode)
{
pinMode(pinNr, mode);
return 0;
}
int PinControl::writeValue(int pinNr, int value, int mode) {
if (mode == 0) {
digitalWrite(pinNr, value);
return 0;
}
if (mode == 1) {
analogWrite(pinNr, value);
return 0;
}
return 1;
int PinControl::writeValue(int pinNr, int value, int mode)
{
if (mode == 0)
{
digitalWrite(pinNr, value);
return 0;
}
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;
int value = 0;
if (mode == 0) {
if (digitalRead(pinNr) == 1){
value = 1;
}
}
if (mode == 1) {
value = analogRead(pinNr);
}
if (mode == 0)
{
if (digitalRead(pinNr) == 1)
{
value = 1;
}
}
if (mode == 1)
{
value = analogRead(pinNr);
}
if (mode == 0 || mode == 1) {
if (mode == 0 || mode == 1)
{
Serial.print("R41");
Serial.print(" ");
Serial.print("P");
Serial.print(pinNr);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
Serial.print("R41");
Serial.print(" ");
Serial.print("P");
Serial.print(pinNr);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
return 0;
}
else {
return 1;
}
return 0;
}
else
{
return 1;
}
}
int PinControl::writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode) {
writeValue( pinNr, valueOne, mode);
delay(time);
writeValue( pinNr, valueTwo, mode);
return 0;
int PinControl::writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode)
{
writeValue(pinNr, valueOne, mode);
delay(time);
writeValue(pinNr, valueTwo, mode);
return 0;
}

View File

@ -16,19 +16,20 @@
#include <stdlib.h>
#include "CurrentState.h"
class PinControl {
class PinControl
{
public:
static PinControl* getInstance();
static PinControl *getInstance();
int setMode(int pinNr, int mode);
int writeValue(int pinNr, int value, int mode);
int readValue(int pinNr, int mode);
int writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode);
int setMode(int pinNr, int mode);
int writeValue(int pinNr, int value, int mode);
int readValue(int pinNr, int mode);
int writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode);
private:
PinControl();
PinControl(PinControl const&);
void operator=(PinControl const&);
PinControl();
PinControl(PinControl const &);
void operator=(PinControl const &);
};
#endif /* PINCONTROL_H_ */

View File

@ -1,39 +1,42 @@
#include "PinGuard.h"
static PinGuard* instance;
static PinGuard *instance;
PinGuard * PinGuard::getInstance() {
if (!instance) {
instance = new PinGuard();
};
return instance;
}
;
PinGuard *PinGuard::getInstance()
{
if (!instance)
{
instance = new PinGuard();
};
return instance;
};
PinGuard::PinGuard() {
pinGuardPin[0] = PinGuardPin();
pinGuardPin[1] = PinGuardPin();
pinGuardPin[2] = PinGuardPin();
pinGuardPin[3] = PinGuardPin();
pinGuardPin[4] = PinGuardPin();
loadConfig();
PinGuard::PinGuard()
{
pinGuardPin[0] = PinGuardPin();
pinGuardPin[1] = PinGuardPin();
pinGuardPin[2] = PinGuardPin();
pinGuardPin[3] = PinGuardPin();
pinGuardPin[4] = PinGuardPin();
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);
pinGuardPin[3].loadPinConfig(PIN_GUARD_4_PIN_NR, PIN_GUARD_4_ACTIVE_STATE, PIN_GUARD_4_TIME_OUT);
pinGuardPin[4].loadPinConfig(PIN_GUARD_5_PIN_NR, PIN_GUARD_5_ACTIVE_STATE, PIN_GUARD_5_TIME_OUT);
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);
pinGuardPin[3].loadPinConfig(PIN_GUARD_4_PIN_NR, PIN_GUARD_4_ACTIVE_STATE, PIN_GUARD_4_TIME_OUT);
pinGuardPin[4].loadPinConfig(PIN_GUARD_5_PIN_NR, PIN_GUARD_5_ACTIVE_STATE, PIN_GUARD_5_TIME_OUT);
}
void PinGuard::checkPins() {
pinGuardPin[0].processTick();
pinGuardPin[1].processTick();
pinGuardPin[2].processTick();
pinGuardPin[3].processTick();
pinGuardPin[4].processTick();
void PinGuard::checkPins()
{
pinGuardPin[0].processTick();
pinGuardPin[1].processTick();
pinGuardPin[2].processTick();
pinGuardPin[3].processTick();
pinGuardPin[4].processTick();
}

View File

@ -17,27 +17,26 @@
#include "PinGuardPin.h"
#include "ParameterList.h"
class PinGuard {
class PinGuard
{
public:
static PinGuard* getInstance();
static PinGuard *getInstance();
void loadConfig();
void checkPins();
void loadConfig();
void checkPins();
private:
//long pinTimeOut[100];
//long pinCurrentTime[100];
//void checkPin;
//bool pinSafeState[100];
PinGuardPin pinGuardPin[5];
//PinGuardPin test;
//long pinTimeOut[100];
//long pinCurrentTime[100];
//void checkPin;
//bool pinSafeState[100];
PinGuardPin pinGuardPin[5];
//PinGuardPin test;
PinGuard();
PinGuard(PinGuard const&);
void operator=(PinGuard const&);
PinGuard();
PinGuard(PinGuard const &);
void operator=(PinGuard const &);
};
#endif /* PINGUARD_H_ */

View File

@ -2,38 +2,44 @@
#include "PinGuardPin.h"
#include "ParameterList.h"
PinGuardPin::PinGuardPin() {
pinNr = 0;
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);
timeOut = ParameterList::getInstance()->getValue(timeOutParamNr);
pinNr = ParameterList::getInstance()->getValue(pinNrParamNr);
activeState = (ParameterList::getInstance()->getValue(activeStateParamNr) == 1);
timeOut = ParameterList::getInstance()->getValue(timeOutParamNr);
timeOutCount = 0;
timeOutCount = 0;
}
// Check each second if the time out is lapsed or the value has changed
void PinGuardPin::processTick() {
void PinGuardPin::processTick()
{
if (pinNr==0) {
return;
}
if (pinNr == 0)
{
return;
}
currentStatePin = digitalRead(pinNr);
currentStatePin = digitalRead(pinNr);
if (currentStatePin != activeState) {
timeOutCount = 0;
} else {
timeOutCount++;
}
if (currentStatePin != activeState)
{
timeOutCount = 0;
}
else
{
timeOutCount++;
}
if (timeOutCount >= timeOut) {
digitalWrite(pinNr, !activeState);
}
if (timeOutCount >= timeOut)
{
digitalWrite(pinNr, !activeState);
}
}

View File

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

View File

@ -7,29 +7,33 @@ Servo pin layout
D11 D6 D5 D4
*/
static ServoControl* instance;
static ServoControl *instance;
Servo servos[2];
ServoControl * ServoControl::getInstance() {
if (!instance) {
instance = new ServoControl();
};
return instance;
}
;
ServoControl *ServoControl::getInstance()
{
if (!instance)
{
instance = new ServoControl();
};
return instance;
};
ServoControl::ServoControl() {
ServoControl::ServoControl()
{
}
int ServoControl::attach() {
servos[0].attach(SERVO_0_PIN);
servos[1].attach(SERVO_1_PIN);
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");
Serial.print(" ");
Serial.print("SERVO");
@ -45,19 +49,17 @@ int ServoControl::setAngle(int pin, int angle) {
Serial.print("\r\n");
*/
switch(pin) {
case 4:
servos[0].write(angle);
break;
case 5:
servos[1].write(angle);
break;
default:
return 1;
}
switch (pin)
{
case 4:
servos[0].write(angle);
break;
case 5:
servos[1].write(angle);
break;
default:
return 1;
}
return 0;
return 0;
}

View File

@ -14,16 +14,18 @@
#include <stdio.h>
#include <stdlib.h>
class ServoControl {
class ServoControl
{
public:
static ServoControl* getInstance();
static ServoControl *getInstance();
int attach();
int setAngle(int pin, int angle);
int attach();
int setAngle(int pin, int angle);
private:
ServoControl();
ServoControl(ServoControl const&);
void operator=(ServoControl const&);
ServoControl();
ServoControl(ServoControl const &);
void operator=(ServoControl const &);
};
#endif /* SERVOCONTROL_H_ */

View File

@ -1,50 +1,49 @@
#include "StatusList.h"
static StatusList* instanceParam;
static StatusList *instanceParam;
long statusValues[150];
StatusList * StatusList::getInstance() {
if (!instanceParam) {
instanceParam = new StatusList();
};
return instanceParam;
StatusList *StatusList::getInstance()
{
if (!instanceParam)
{
instanceParam = new StatusList();
};
return instanceParam;
}
StatusList::StatusList() {
StatusList::StatusList()
{
statusValues[STATUS_GENERAL] = STATUS_GENERAL_DEFAULT;
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;
//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];
long value = statusValues[id];
Serial.print("R31");
Serial.print(" ");
Serial.print("P");
Serial.print(id);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
Serial.print("R31");
Serial.print(" ");
Serial.print("P");
Serial.print(id);
Serial.print(" ");
Serial.print("V");
Serial.print(value);
//Serial.print("\r\n");
CurrentState::getInstance()->printQAndNewLine();
return 0;
return 0;
}
long StatusList::getValue(int id)
{
long StatusList::getValue(int id) {
/*
/*
Serial.print("R99");
Serial.print(" ");
Serial.print("getValue");
@ -55,13 +54,13 @@ long StatusList::getValue(int id) {
Serial.print("\r\n");
*/
return statusValues[id];
return statusValues[id];
}
int StatusList::setValue(int id, long value) {
int StatusList::setValue(int id, long value)
{
statusValues[id] = value;
statusValues[id] = value;
return 0;
return 0;
}

View File

@ -7,14 +7,13 @@
//#define NULL 0
enum StatusListEnum
{
STATUS_GENERAL = 0,
STATUS_GENERAL = 0,
//MOVEMENT_MAX_SPD_X = 71,
//MOVEMENT_MAX_SPD_Y = 72,
//MOVEMENT_MAX_SPD_Z = 73
//MOVEMENT_MAX_SPD_X = 71,
//MOVEMENT_MAX_SPD_Y = 72,
//MOVEMENT_MAX_SPD_Z = 73
};
@ -22,19 +21,21 @@ enum StatusListEnum
#define NULL 0
*/
class StatusList {
StatusListEnum statusListEnum;
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);
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&);
StatusList();
StatusList(StatusList const &);
void operator=(StatusList const &);
};
#endif /* STATUSLIST_H_ */

File diff suppressed because it is too large Load Diff

View File

@ -19,87 +19,87 @@
#include <stdlib.h>
#include "Command.h"
class StepperControl {
class StepperControl
{
public:
StepperControl();
StepperControl(StepperControl const&);
void operator=(StepperControl const&);
StepperControl();
StepperControl(StepperControl const &);
void operator=(StepperControl const &);
static StepperControl* getInstance();
//int moveAbsolute( long xDest, long yDest,long zDest,
// unsigned int maxStepsPerSecond,
// 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
);
static StepperControl *getInstance();
//int moveAbsolute( long xDest, long yDest,long zDest,
// unsigned int maxStepsPerSecond,
// 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);
void handleMovementInterrupt();
int calibrateAxis(int axis);
void initInterrupt();
void enableMotors();
void disableMotors();
bool motorsEnabled();
void handleMovementInterrupt();
int calibrateAxis(int axis);
void initInterrupt();
void enableMotors();
void disableMotors();
bool motorsEnabled();
void storePosition();
void loadSettings();
void storePosition();
void loadSettings();
void setPositionX(long pos);
void setPositionY(long pos);
void setPositionZ(long pos);
void setPositionX(long pos);
void setPositionY(long pos);
void setPositionZ(long pos);
void test();
void test2();
void test();
void test2();
private:
StepperControlAxis axisX;
StepperControlAxis axisY;
StepperControlAxis axisZ;
StepperControlAxis axisX;
StepperControlAxis axisY;
StepperControlAxis axisZ;
StepperControlEncoder encoderX;
StepperControlEncoder encoderY;
StepperControlEncoder encoderZ;
StepperControlEncoder encoderX;
StepperControlEncoder encoderY;
StepperControlEncoder encoderZ;
void checkAxisVsEncoder(StepperControlAxis* axis, StepperControlEncoder* encoder, float* missedSteps, long* lastPosition, float* encoderStepDecay, bool* encoderEnabled);
void checkAxisSubStatus(StepperControlAxis* axis, int* axisSubStatus);
void checkAxisVsEncoder(StepperControlAxis *axis, StepperControlEncoder *encoder, float *missedSteps, long *lastPosition, float *encoderStepDecay, bool *encoderEnabled);
void checkAxisSubStatus(StepperControlAxis *axis, int *axisSubStatus);
bool axisActive[3];
int axisSubStep[3];
bool axisActive[3];
int axisSubStep[3];
void loadMotorSettings();
void loadEncoderSettings();
bool intToBool(int value);
void loadMotorSettings();
void loadEncoderSettings();
bool intToBool(int value);
void reportPosition();
void storeEndStops();
void reportEndStops();
void reportStatus(StepperControlAxis* axis, int axisSubStatus);
void reportCalib(StepperControlAxis* axis, int calibStatus);
void reportPosition();
void storeEndStops();
void reportEndStops();
void reportStatus(StepperControlAxis *axis, int axisSubStatus);
void reportCalib(StepperControlAxis *axis, int calibStatus);
unsigned long getMaxLength(unsigned long lengths[3]);
bool endStopsReached();
unsigned long getMaxLength(unsigned long lengths[3]);
bool endStopsReached();
bool homeIsUp[3];
long speedMax[3];
long speedMin[3];
long stepsAcc[3];
bool motorInv[3];
bool motor2Inv[3];
bool motor2Enbl[3];
bool endStInv[3];
bool endStEnbl[3];
long timeOut[3];
bool homeIsUp[3];
long speedMax[3];
long speedMin[3];
long stepsAcc[3];
bool motorInv[3];
bool motor2Inv[3];
bool motor2Enbl[3];
bool endStInv[3];
bool endStEnbl[3];
long timeOut[3];
float motorConsMissedSteps[3];
long motorLastPosition[3];
float motorConsMissedSteps[3];
long motorLastPosition[3];
int motorConsMissedStepsMax[3];
float motorConsMissedStepsDecay[3];
bool motorConsEncoderEnabled[3];
int motorConsEncoderType[3];
int motorConsEncoderScaling[3];
int motorConsMissedStepsMax[3];
float motorConsMissedStepsDecay[3];
bool motorConsEncoderEnabled[3];
int motorConsEncoderType[3];
int motorConsEncoderScaling[3];
bool motorMotorsEnabled;
bool motorMotorsEnabled;
};
#endif /* STEPPERCONTROL_H_ */

View File

@ -1,507 +1,611 @@
#include "StepperControlAxis.h"
StepperControlAxis::StepperControlAxis() {
lastCalcLog = 0;
StepperControlAxis::StepperControlAxis()
{
lastCalcLog = 0;
pinStep = 0;
pinDirection = 0;
pinEnable = 0;
pinStep = 0;
pinDirection = 0;
pinEnable = 0;
pin2Step = 0;
pin2Direction = 0;
pin2Enable = 0;
pin2Step = 0;
pin2Direction = 0;
pin2Enable = 0;
pinMin = 0;
pinMax = 0;
pinMin = 0;
pinMax = 0;
axisActive = false;
axisActive = false;
coordSourcePoint = 0;
coordCurrentPoint = 0;
coordDestinationPoint = 0;
coordHomeAxis = 0;
coordSourcePoint = 0;
coordCurrentPoint = 0;
coordDestinationPoint = 0;
coordHomeAxis = 0;
movementUp = false;
movementToHome = false;
movementAccelerating = false;
movementDecelerating = false;
movementCruising = false;
movementCrawling = false;
movementMotorActive = false;
movementMoving = false;
movementUp = false;
movementToHome = false;
movementAccelerating = false;
movementDecelerating = false;
movementCruising = false;
movementCrawling = false;
movementMotorActive = false;
movementMoving = false;
}
void StepperControlAxis::test() {
Serial.print("R99");
Serial.print(" cur loc = ");
Serial.print(coordCurrentPoint);
//Serial.print(" enc loc = ");
//Serial.print(coordEncoderPoint);
//Serial.print(" cons steps missed = ");
//Serial.print(label);
//Serial.print(consMissedSteps);
Serial.print("\r\n");
void StepperControlAxis::test()
{
Serial.print("R99");
Serial.print(" cur loc = ");
Serial.print(coordCurrentPoint);
//Serial.print(" enc loc = ");
//Serial.print(coordEncoderPoint);
//Serial.print(" cons steps missed = ");
//Serial.print(label);
//Serial.print(consMissedSteps);
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;
int newSpeed = 0;
long curPos = abs(currentPosition);
long curPos = abs(currentPosition);
long staPos;
long endPos;
long staPos;
long endPos;
movementAccelerating = false;
movementDecelerating = false;
movementCruising = false;
movementCrawling = false;
movementMoving = false;
movementAccelerating = false;
movementDecelerating = false;
movementCruising = false;
movementCrawling = false;
movementMoving = false;
if (abs(sourcePosition) < abs(destinationPosition))
{
staPos = abs(sourcePosition);
endPos = abs(destinationPosition);
;
}
else
{
staPos = abs(destinationPosition);
;
endPos = abs(sourcePosition);
}
if (abs(sourcePosition) < abs(destinationPosition)) {
staPos = abs(sourcePosition);
endPos = abs(destinationPosition);;
} else {
staPos = abs(destinationPosition);;
endPos = abs(sourcePosition);
}
unsigned long halfway = ((endPos - staPos) / 2) + staPos;
unsigned long halfway = ((endPos - staPos) / 2) + staPos;
// Set the minimum speed if the position would be out of bounds
if (curPos < staPos || curPos > endPos)
{
newSpeed = minSpeed;
movementCrawling = true;
movementMoving = true;
}
else
{
if (curPos >= staPos && curPos <= halfway)
{
// accelerating
if (curPos > (staPos + stepsAccDec))
{
// now beyond the accelleration point to go full speed
newSpeed = maxSpeed + 1;
movementCruising = true;
movementMoving = true;
}
else
{
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (curPos - staPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementAccelerating = true;
movementMoving = true;
}
}
else
{
// decelerating
if (curPos < (endPos - stepsAccDec))
{
// still before the deceleration point so keep going at full speed
newSpeed = maxSpeed + 2;
movementCruising = true;
movementMoving = true;
}
else
{
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (endPos - curPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementDecelerating = true;
movementMoving = true;
}
}
}
// Set the minimum speed if the position would be out of bounds
if (curPos < staPos || curPos > endPos) {
newSpeed = minSpeed;
movementCrawling = true;
movementMoving = true;
} else {
if (curPos >= staPos && curPos <= halfway) {
// accelerating
if (curPos > (staPos + stepsAccDec)) {
// now beyond the accelleration point to go full speed
newSpeed = maxSpeed + 1;
movementCruising = true;
movementMoving = true;
} else {
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (curPos - staPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementAccelerating = true;
movementMoving = true;
}
} else {
// decelerating
if (curPos < (endPos - stepsAccDec)) {
// still before the deceleration point so keep going at full speed
newSpeed = maxSpeed + 2;
movementCruising = true;
movementMoving = true;
} else {
// speeding up, increase speed linear within the first period
newSpeed = (1.0 * (endPos - curPos) / stepsAccDec * (maxSpeed - minSpeed)) + minSpeed;
movementDecelerating = true;
movementMoving = true;
}
}
}
if (debugPrint && (millis() - lastCalcLog > 1000))
{
lastCalcLog = millis();
if (debugPrint && (millis() - lastCalcLog > 1000)) {
Serial.print("R99");
lastCalcLog = millis();
Serial.print(" sta ");
Serial.print(staPos);
Serial.print(" cur ");
Serial.print(curPos);
Serial.print(" end ");
Serial.print(endPos);
Serial.print(" half ");
Serial.print(halfway);
Serial.print(" len ");
Serial.print(stepsAccDec);
Serial.print(" min ");
Serial.print(minSpeed);
Serial.print(" max ");
Serial.print(maxSpeed);
Serial.print(" spd ");
Serial.print("R99");
Serial.print(" ");
Serial.print(newSpeed);
Serial.print(" sta ");
Serial.print(staPos);
Serial.print(" cur ");
Serial.print(curPos);
Serial.print(" end ");
Serial.print(endPos);
Serial.print(" half ");
Serial.print(halfway);
Serial.print(" len ");
Serial.print(stepsAccDec);
Serial.print(" min ");
Serial.print(minSpeed);
Serial.print(" max ");
Serial.print(maxSpeed);
Serial.print(" spd ");
Serial.print("\r\n");
}
Serial.print(" ");
Serial.print(newSpeed);
Serial.print("\r\n");
}
// Return the calculated speed, in steps per second
return newSpeed;
// Return the calculated speed, in steps per second
return newSpeed;
}
void StepperControlAxis::checkAxisDirection() {
void StepperControlAxis::checkAxisDirection()
{
if (coordHomeAxis){
// When home is active, the direction is fixed
movementUp = motorHomeIsUp;
movementToHome = true;
} else {
// For normal movement, move in direction of destination
movementUp = ( coordCurrentPoint < coordDestinationPoint );
movementToHome = (abs(coordCurrentPoint) >= abs(coordDestinationPoint));
}
if (coordHomeAxis)
{
// When home is active, the direction is fixed
movementUp = motorHomeIsUp;
movementToHome = true;
}
else
{
// For normal movement, move in direction of destination
movementUp = (coordCurrentPoint < coordDestinationPoint);
movementToHome = (abs(coordCurrentPoint) >= abs(coordDestinationPoint));
}
if (coordCurrentPoint == 0) {
// Go slow when theoretical end point reached but there is no end stop siganl
axisSpeed = motorSpeedMin;
}
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) {
setDirectionUp();
} else {
setDirectionDown();
}
if (((!coordHomeAxis && coordCurrentPoint < coordDestinationPoint) || (coordHomeAxis && motorHomeIsUp)) ^ motorMotorInv)
{
setDirectionUp();
}
else
{
setDirectionDown();
}
}
void StepperControlAxis::checkMovement() {
void StepperControlAxis::checkMovement()
{
checkAxisDirection();
checkAxisDirection();
// Handle movement if destination is not already reached or surpassed
if (
(
(coordDestinationPoint > coordSourcePoint && coordCurrentPoint < coordDestinationPoint) ||
(coordDestinationPoint < coordSourcePoint && coordCurrentPoint > coordDestinationPoint) ||
coordHomeAxis
)
&& axisActive
) {
// Handle movement if destination is not already reached or surpassed
if (
(
(coordDestinationPoint > coordSourcePoint && coordCurrentPoint < coordDestinationPoint) ||
(coordDestinationPoint < coordSourcePoint && coordCurrentPoint > coordDestinationPoint) ||
coordHomeAxis) &&
axisActive)
{
// home or destination not reached, keep moving
// 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 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)))
{
// Get the axis speed, in steps per second
axisSpeed = calculateSpeed( coordSourcePoint, coordCurrentPoint, coordDestinationPoint,
motorSpeedMin, motorSpeedMax, motorStepsAcc);
// Get the axis speed, in steps per second
axisSpeed = calculateSpeed(coordSourcePoint, coordCurrentPoint, coordDestinationPoint,
motorSpeedMin, motorSpeedMax, motorStepsAcc);
// Set the moments when the step is set to true and false
if (axisSpeed > 0)
{
// Set the moments when the step is set to true and false
if (axisSpeed > 0)
{
// Take the requested speed (steps / second) and divide by the interrupt speed (interrupts per seconde)
// This gives the number of interrupts (called ticks here) before the pulse needs to be set for the next step
stepOnTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed / 2);
stepOffTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed );
}
}
else {
axisActive = false;
}
// Take the requested speed (steps / second) and divide by the interrupt speed (interrupts per seconde)
// This gives the number of interrupts (called ticks here) before the pulse needs to be set for the next step
stepOnTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed / 2);
stepOffTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed);
}
}
else
{
axisActive = false;
}
}
else
{
// Destination or home reached. Deactivate the axis.
axisActive = false;
}
} 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)) {
coordCurrentPoint = 0;
}
// If end stop for home is active, set the position to zero
if (endStopAxisReached(false))
{
coordCurrentPoint = 0;
}
}
void StepperControlAxis::checkTiming() {
void StepperControlAxis::checkTiming()
{
//int i;
//int i;
if (axisActive) {
if (axisActive)
{
moveTicks++;
moveTicks++;
if (moveTicks >= stepOffTick) {
if (moveTicks >= stepOffTick)
{
// Negative flank for the steps
resetMotorStep();
checkMovement();
}
else {
// Negative flank for the steps
resetMotorStep();
checkMovement();
}
else
{
if (moveTicks == stepOnTick) {
if (moveTicks == stepOnTick)
{
// Positive flank for the steps
setStepAxis();
}
}
}
// Positive flank for the steps
setStepAxis();
}
}
}
}
void StepperControlAxis::setStepAxis() {
void StepperControlAxis::setStepAxis()
{
if (movementUp) {
coordCurrentPoint++;
} else {
coordCurrentPoint--;
}
if (movementUp)
{
coordCurrentPoint++;
}
else
{
coordCurrentPoint--;
}
// set a step on the motors
setMotorStep();
// set a step on the motors
setMotorStep();
}
bool StepperControlAxis::endStopAxisReached(bool movement_forward) {
bool StepperControlAxis::endStopAxisReached(bool movement_forward)
{
bool min_endstop = false;
bool max_endstop = false;
bool invert = false;
bool min_endstop = false;
bool max_endstop = false;
bool invert = false;
if (motorEndStopInv) {
invert = true;
}
if (motorEndStopInv)
{
invert = true;
}
// for the axis to check, retrieve the end stop status
// for the axis to check, retrieve the end stop status
if (!invert) {
min_endstop = endStopMin();
max_endstop = endStopMax();
} else {
min_endstop = endStopMax();
max_endstop = endStopMin();
}
if (!invert)
{
min_endstop = endStopMin();
max_endstop = endStopMax();
}
else
{
min_endstop = endStopMax();
max_endstop = endStopMin();
}
// if moving forward, only check the end stop max
// for moving backwards, check only the end stop min
// 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)) {
return 1;
}
if ((!movement_forward && min_endstop) || (movement_forward && max_endstop))
{
return 1;
}
return 0;
return 0;
}
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;
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;
pin2Step = step2;
pin2Direction = dir2;
pin2Enable = enable2;
pin2Step = step2;
pin2Direction = dir2;
pin2Enable = enable2;
pinMin = min;
pinMax = max;
pinMin = min;
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)
{
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) {
motorSpeedMax = speedMax;
motorSpeedMin = speedMin;
motorStepsAcc = stepsAcc;
motorTimeOut = timeOut;
motorHomeIsUp = homeIsUp;
motorMotorInv = motorInv;
motorEndStopInv = endStInv;
motorEndStopEnbl = endStEnbl;
motorInterruptSpeed = interruptSpeed;
motorMotor2Enl = motor2Enbl;
motorMotor2Inv = motor2Inv;
motorSpeedMax = speedMax;
motorSpeedMin = speedMin;
motorStepsAcc = stepsAcc;
motorTimeOut = timeOut;
motorHomeIsUp = homeIsUp;
motorMotorInv = motorInv;
motorEndStopInv = endStInv;
motorEndStopEnbl = endStEnbl;
motorInterruptSpeed = interruptSpeed;
motorMotor2Enl = motor2Enbl;
motorMotor2Inv = motor2Inv;
}
void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint, bool home) {
void StepperControlAxis::loadCoordinates(long sourcePoint, long destinationPoint, bool home)
{
coordSourcePoint = sourcePoint;
coordCurrentPoint = sourcePoint;
coordDestinationPoint = destinationPoint;
coordHomeAxis = home;
coordSourcePoint = sourcePoint;
coordCurrentPoint = sourcePoint;
coordDestinationPoint = destinationPoint;
coordHomeAxis = home;
// Limit normal movmement to the home position
if (!motorHomeIsUp && coordDestinationPoint < 0) {
coordDestinationPoint = 0;
}
// Limit normal movmement to the home position
if (!motorHomeIsUp && coordDestinationPoint < 0)
{
coordDestinationPoint = 0;
}
if ( motorHomeIsUp && coordDestinationPoint > 0) {
coordDestinationPoint = 0;
}
if (motorHomeIsUp && coordDestinationPoint > 0)
{
coordDestinationPoint = 0;
}
// Initialize movement variables
moveTicks = 0;
axisActive = true;
// Initialize movement variables
moveTicks = 0;
axisActive = true;
}
void StepperControlAxis::enableMotor() {
digitalWrite(pinEnable, LOW);
if (motorMotor2Enl) {
digitalWrite(pin2Enable, LOW);
}
movementMotorActive = true;
void StepperControlAxis::enableMotor()
{
digitalWrite(pinEnable, LOW);
if (motorMotor2Enl)
{
digitalWrite(pin2Enable, LOW);
}
movementMotorActive = true;
}
void StepperControlAxis::disableMotor() {
digitalWrite(pinEnable, HIGH);
if (motorMotor2Enl) {
digitalWrite(pin2Enable, HIGH);
}
movementMotorActive = false;
void StepperControlAxis::disableMotor()
{
digitalWrite(pinEnable, HIGH);
if (motorMotor2Enl)
{
digitalWrite(pin2Enable, HIGH);
}
movementMotorActive = false;
}
void StepperControlAxis::setDirectionUp() {
if (motorMotorInv) {
digitalWrite(pinDirection, LOW);
} else {
digitalWrite(pinDirection, HIGH);
}
void StepperControlAxis::setDirectionUp()
{
if (motorMotorInv)
{
digitalWrite(pinDirection, LOW);
}
else
{
digitalWrite(pinDirection, HIGH);
}
if (motorMotor2Enl && motorMotor2Inv) {
digitalWrite(pin2Direction, LOW);
} else {
digitalWrite(pin2Direction, HIGH);
}
if (motorMotor2Enl && motorMotor2Inv)
{
digitalWrite(pin2Direction, LOW);
}
else
{
digitalWrite(pin2Direction, HIGH);
}
}
void StepperControlAxis::setDirectionDown() {
if (motorMotorInv) {
digitalWrite(pinDirection, HIGH);
} else {
digitalWrite(pinDirection, LOW);
}
void StepperControlAxis::setDirectionDown()
{
if (motorMotorInv)
{
digitalWrite(pinDirection, HIGH);
}
else
{
digitalWrite(pinDirection, LOW);
}
if (motorMotor2Enl && motorMotor2Inv) {
digitalWrite(pin2Direction, HIGH);
} else {
digitalWrite(pin2Direction, LOW);
}
if (motorMotor2Enl && motorMotor2Inv)
{
digitalWrite(pin2Direction, HIGH);
}
else
{
digitalWrite(pin2Direction, LOW);
}
}
void StepperControlAxis::setMovementUp() {
movementUp = true;
void StepperControlAxis::setMovementUp()
{
movementUp = true;
}
void StepperControlAxis::setMovementDown() {
movementUp = false;
void StepperControlAxis::setMovementDown()
{
movementUp = false;
}
void StepperControlAxis::setDirectionHome() {
if (motorHomeIsUp) {
setDirectionUp();
setMovementUp();
} else {
setDirectionDown();
setMovementDown();
}
void StepperControlAxis::setDirectionHome()
{
if (motorHomeIsUp)
{
setDirectionUp();
setMovementUp();
}
else
{
setDirectionDown();
setMovementDown();
}
}
void StepperControlAxis::setDirectionAway() {
if (motorHomeIsUp) {
setDirectionDown();
setMovementDown();
} else {
setDirectionUp();
setMovementUp();
}
void StepperControlAxis::setDirectionAway()
{
if (motorHomeIsUp)
{
setDirectionDown();
setMovementDown();
}
else
{
setDirectionUp();
setMovementUp();
}
}
unsigned long StepperControlAxis::getLength(long l1, long l2) {
if (l1 > l2) {
return l1 - l2;
} else {
return l2 - l1;
}
unsigned long StepperControlAxis::getLength(long l1, long l2)
{
if (l1 > l2)
{
return l1 - l2;
}
else
{
return l2 - l1;
}
}
bool StepperControlAxis::endStopsReached() {
return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv)) && motorEndStopEnbl;
bool StepperControlAxis::endStopsReached()
{
return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv)) && motorEndStopEnbl;
}
bool StepperControlAxis::endStopMin() {
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMin) && motorEndStopEnbl;
bool StepperControlAxis::endStopMin()
{
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMin) && motorEndStopEnbl;
}
bool StepperControlAxis::endStopMax() {
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMax) && motorEndStopEnbl;
bool StepperControlAxis::endStopMax()
{
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
return digitalRead(pinMax) && motorEndStopEnbl;
}
bool StepperControlAxis::isAxisActive() {
return axisActive;
bool StepperControlAxis::isAxisActive()
{
return axisActive;
}
void StepperControlAxis::deactivateAxis() {
axisActive = false;
void StepperControlAxis::deactivateAxis()
{
axisActive = false;
}
void StepperControlAxis::setMotorStep() {
digitalWrite(pinStep, HIGH);
if (pin2Enable) {
digitalWrite(pin2Step, HIGH);
}
void StepperControlAxis::setMotorStep()
{
digitalWrite(pinStep, HIGH);
if (pin2Enable)
{
digitalWrite(pin2Step, HIGH);
}
}
void StepperControlAxis::resetMotorStep() {
movementStepDone = true;
digitalWrite(pinStep, LOW);
if (pin2Enable) {
digitalWrite(pin2Step, LOW);
}
void StepperControlAxis::resetMotorStep()
{
movementStepDone = true;
digitalWrite(pinStep, LOW);
if (pin2Enable)
{
digitalWrite(pin2Step, LOW);
}
}
bool StepperControlAxis::pointReached(long currentPoint, long destinationPoint) {
return (destinationPoint == currentPoint);
bool StepperControlAxis::pointReached(long currentPoint, long destinationPoint)
{
return (destinationPoint == currentPoint);
}
long StepperControlAxis::currentPosition() {
return coordCurrentPoint;
long StepperControlAxis::currentPosition()
{
return coordCurrentPoint;
}
void StepperControlAxis::setCurrentPosition(long newPos) {
coordCurrentPoint = newPos;
void StepperControlAxis::setCurrentPosition(long newPos)
{
coordCurrentPoint = newPos;
}
void StepperControlAxis::setMaxSpeed(long speed) {
motorSpeedMax = speed;
void StepperControlAxis::setMaxSpeed(long speed)
{
motorSpeedMax = speed;
}
void StepperControlAxis::activateDebugPrint() {
debugPrint = true;
void StepperControlAxis::activateDebugPrint()
{
debugPrint = true;
}
bool StepperControlAxis::isStepDone() {
return movementStepDone;
bool StepperControlAxis::isStepDone()
{
return movementStepDone;
}
void StepperControlAxis::resetStepDone() {
movementStepDone = false;
void StepperControlAxis::resetStepDone()
{
movementStepDone = false;
}
bool StepperControlAxis::movingToHome() {
return movementToHome;
bool StepperControlAxis::movingToHome()
{
return movementToHome;
}
bool StepperControlAxis::movingUp() {
return movementUp;
bool StepperControlAxis::movingUp()
{
return movementUp;
}
bool StepperControlAxis::isAccelerating() {
return movementAccelerating;
bool StepperControlAxis::isAccelerating()
{
return movementAccelerating;
}
bool StepperControlAxis::isDecelerating() {
return movementDecelerating;
bool StepperControlAxis::isDecelerating()
{
return movementDecelerating;
}
bool StepperControlAxis::isCruising() {
return movementCruising;
bool StepperControlAxis::isCruising()
{
return movementCruising;
}
bool StepperControlAxis::isCrawling() {
return movementCrawling;
bool StepperControlAxis::isCrawling()
{
return movementCrawling;
}
bool StepperControlAxis::isMotorActive() {
return movementMotorActive;
bool StepperControlAxis::isMotorActive()
{
return movementMotorActive;
}

View File

@ -17,130 +17,127 @@
#include <stdio.h>
#include <stdlib.h>
class StepperControlAxis {
class StepperControlAxis
{
public:
StepperControlAxis();
StepperControlAxis();
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);
void loadMotorSettings(long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv, bool endStInv, long interruptSpeed, bool motor2Enbl, bool motor2Inv, bool endStEnbl);
void loadCoordinates(long sourcePoint, long destinationPoint, bool home);
void setMaxSpeed(long speed);
void loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2);
void loadMotorSettings( long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv, bool endStInv, long interruptSpeed, bool motor2Enbl, bool motor2Inv, bool endStEnbl);
void loadCoordinates(long sourcePoint, long destinationPoint, bool home);
void setMaxSpeed(long speed);
void enableMotor();
void disableMotor();
void checkMovement();
void checkTiming();
void enableMotor();
void disableMotor();
void checkMovement();
void checkTiming();
bool isAxisActive();
void deactivateAxis();
bool isAccelerating();
bool isDecelerating();
bool isCruising();
bool isCrawling();
bool isMotorActive();
bool isMoving();
bool isAxisActive();
void deactivateAxis();
bool isAccelerating();
bool isDecelerating();
bool isCruising();
bool isCrawling();
bool isMotorActive();
bool isMoving();
bool endStopMin();
bool endStopMax();
bool endStopsReached();
bool endStopAxisReached(bool movement_forward);
bool endStopMin();
bool endStopMax();
bool endStopsReached();
bool endStopAxisReached(bool movement_forward);
long currentPosition();
void setCurrentPosition(long newPos);
long currentPosition();
void setCurrentPosition(long newPos);
void setStepAxis();
void setMotorStep();
void resetMotorStep();
void setStepAxis();
void setMotorStep();
void resetMotorStep();
void setDirectionUp();
void setDirectionDown();
void setDirectionHome();
void setDirectionAway();
void setDirectionAxis();
void setDirectionUp();
void setDirectionDown();
void setDirectionHome();
void setDirectionAway();
void setDirectionAxis();
void setMovementUp();
void setMovementDown();
void setMovementUp();
void setMovementDown();
bool movingToHome();
bool movingUp();
bool movingToHome();
bool movingUp();
bool isStepDone();
void resetStepDone();
bool isStepDone();
void resetStepDone();
void activateDebugPrint();
void test();
void activateDebugPrint();
void test();
char label;
bool movementStarted;
char label;
bool movementStarted;
private:
int lastCalcLog = 0;
bool debugPrint = false;
int lastCalcLog = 0;
bool debugPrint = false;
// pin settings primary motor
int pinStep;
int pinDirection;
int pinEnable;
// pin settings primary motor
int pinStep;
int pinDirection;
int pinEnable;
// pin settings primary motor
int pin2Step;
int pin2Direction;
int pin2Enable;
// pin settings primary motor
int pin2Step;
int pin2Direction;
int pin2Enable;
// pin settings primary motor
int pinMin;
int pinMax;
// pin settings primary motor
int pinMin;
int pinMax;
// motor settings
bool motorEndStopInv; // invert input (true/false) of end stops
bool motorEndStopEnbl; // enable the use of the end stops
// motor settings
bool motorEndStopInv; // invert input (true/false) of end stops
bool motorEndStopEnbl; // enable the use of the end stops
// motor settings
long motorSpeedMax; // maximum speed in steps per second
long motorSpeedMin; // minimum speed in steps per second
long motorStepsAcc; // number of steps used for acceleration
long motorTimeOut; // timeout in seconds
bool motorHomeIsUp; // direction to move when reached 0 on axis but no end stop detected while homing
bool motorMotorInv; // invert motor direction
bool motorMotor2Enl; // enable secondary motor
bool motorMotor2Inv; // invert secondary motor direction
long motorInterruptSpeed; // period of interrupt in micro seconds
// motor settings
long motorSpeedMax; // maximum speed in steps per second
long motorSpeedMin; // minimum speed in steps per second
long motorStepsAcc; // number of steps used for acceleration
long motorTimeOut; // timeout in seconds
bool motorHomeIsUp; // direction to move when reached 0 on axis but no end stop detected while homing
bool motorMotorInv; // invert motor direction
bool motorMotor2Enl; // enable secondary motor
bool motorMotor2Inv; // invert secondary motor direction
long motorInterruptSpeed; // period of interrupt in micro seconds
// coordinates
long coordSourcePoint; // all coordinated in steps
long coordCurrentPoint;
long coordDestinationPoint;
bool coordHomeAxis; // homing command
// coordinates
long coordSourcePoint; // all coordinated in steps
long coordCurrentPoint;
long coordDestinationPoint;
bool coordHomeAxis; // homing command
// movement handling
unsigned long movementLength;
unsigned long maxLenth;
unsigned long moveTicks;
unsigned long stepOnTick;
unsigned long stepOffTick;
unsigned long axisSpeed;
// movement handling
unsigned long movementLength;
unsigned long maxLenth;
unsigned long moveTicks;
unsigned long stepOnTick;
unsigned long stepOffTick;
unsigned long axisSpeed;
bool axisActive;
bool movementUp;
bool movementToHome;
bool movementStepDone;
bool movementAccelerating;
bool movementDecelerating;
bool movementCruising;
bool movementCrawling;
bool movementMotorActive;
bool movementMoving;
void step(long &currentPoint, unsigned long steps, long destinationPoint);
bool pointReached(long currentPoint, long destinationPoint);
unsigned int calculateSpeed(long sourcePosition, long currentPosition, long destinationPosition, long minSpeed, long maxSpeed, long stepsAccDec);
unsigned long getLength(long l1, long l2);
void checkAxisDirection();
bool axisActive;
bool movementUp;
bool movementToHome;
bool movementStepDone;
bool movementAccelerating;
bool movementDecelerating;
bool movementCruising;
bool movementCrawling;
bool movementMotorActive;
bool movementMoving;
void step(long &currentPoint, unsigned long steps, long destinationPoint);
bool pointReached(long currentPoint, long destinationPoint);
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,28 +1,30 @@
#include "StepperControlEncoder.h"
StepperControlEncoder::StepperControlEncoder() {
//lastCalcLog = 0;
StepperControlEncoder::StepperControlEncoder()
{
//lastCalcLog = 0;
pinChannelA = 0;
pinChannelB = 0;
pinChannelA = 0;
pinChannelB = 0;
position = 0;
encoderType = 0; // default type
scalingFactor = 100;
position = 0;
encoderType = 0; // default type
scalingFactor = 100;
curValChannelA = false;
curValChannelA = false;
prvValChannelA = false;
prvValChannelA = false;
curValChannelA = false;
curValChannelA = false;
prvValChannelA = false;
prvValChannelA = false;
readChannelA = false;
readChannelAQ = false;
readChannelB = false;
readChannelBQ = false;
readChannelA = false;
readChannelAQ = false;
readChannelB = false;
readChannelBQ = false;
}
void StepperControlEncoder::test() {
/*
void StepperControlEncoder::test()
{
/*
Serial.print("R88 ");
Serial.print("position ");
Serial.print(position);
@ -38,34 +40,41 @@ void StepperControlEncoder::test() {
*/
}
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ) {
pinChannelA = channelA;
pinChannelB = channelB;
pinChannelAQ = channelAQ;
pinChannelBQ = channelBQ;
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ)
{
pinChannelA = channelA;
pinChannelB = channelB;
pinChannelAQ = channelAQ;
pinChannelBQ = channelBQ;
readChannels();
shiftChannels();
readChannels();
shiftChannels();
}
void StepperControlEncoder::loadSettings(int encType, int scaling) {
encoderType = encType;
scalingFactor = scaling;
void StepperControlEncoder::loadSettings(int encType, int scaling)
{
encoderType = encType;
scalingFactor = scaling;
}
void StepperControlEncoder::setPosition(long newPosition) {
position = 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
// Apply scaling to the output of the encoder, except when scaling is zero or lower
if (scalingFactor == 100 || scalingFactor <= 0) {
return position;
} else {
return position * scalingFactor / 100;
}
if (scalingFactor == 100 || scalingFactor <= 0)
{
return position;
}
else
{
return position * scalingFactor / 100;
}
}
/* Check the encoder channels for movement accoridng to thisspecification
@ -83,69 +92,95 @@ rotation ----------------------------------------------------->
*/
void StepperControlEncoder::readEncoder()
{
void StepperControlEncoder::readEncoder() {
// save the old values, read the new values
shiftChannels();
readChannels();
// save the old values, read the new values
shiftChannels();
readChannels();
int delta = 0;
int delta = 0;
// 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++;
}
// 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 == 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() {
void StepperControlEncoder::readChannels()
{
// read the new values from the coder
// read the new values from the coder
readChannelA = digitalRead(pinChannelA);
readChannelAQ = digitalRead(pinChannelAQ);
readChannelB = digitalRead(pinChannelB);
readChannelBQ = digitalRead(pinChannelBQ);
readChannelA = digitalRead(pinChannelA);
readChannelAQ = digitalRead(pinChannelAQ);
readChannelB = digitalRead(pinChannelB);
readChannelBQ = digitalRead(pinChannelBQ);
if (encoderType == 1) {
if (encoderType == 1)
{
// differential encoder
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ)) {
curValChannelA = readChannelA;
curValChannelB = readChannelB;
}
}
else {
// differential encoder
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ))
{
curValChannelA = readChannelA;
curValChannelB = readChannelB;
}
}
else
{
// encoderType <= 0
// non-differential incremental encoder
curValChannelA = readChannelA;
curValChannelB = readChannelB;
}
// encoderType <= 0
// non-differential incremental encoder
curValChannelA = readChannelA;
curValChannelB = readChannelB;
}
//curValChannelA = readChannelA;
//curValChannelB = readChannelB;
//curValChannelA = readChannelA;
//curValChannelB = readChannelB;
// curValChannelA = digitalRead(pinChannelA);
// curValChannelB = digitalRead(pinChannelB);
// curValChannelA = digitalRead(pinChannelA);
// curValChannelB = digitalRead(pinChannelB);
}
void StepperControlEncoder::shiftChannels() {
void StepperControlEncoder::shiftChannels()
{
// Save the current enoder status to later on compare with new values
// Save the current enoder status to later on compare with new values
prvValChannelA = curValChannelA;
prvValChannelB = curValChannelB;
prvValChannelA = curValChannelA;
prvValChannelB = curValChannelB;
}

View File

@ -16,48 +16,45 @@
#include <stdio.h>
#include <stdlib.h>
class StepperControlEncoder {
class StepperControlEncoder
{
public:
StepperControlEncoder();
StepperControlEncoder();
void loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ);
void loadSettings(int encType, int scaling);
void loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ);
void loadSettings(int encType, int scaling);
void setPosition(long newPosition);
long currentPosition();
void setPosition(long newPosition);
long currentPosition();
void readEncoder();
void readChannels();
void shiftChannels();
void test();
void readEncoder();
void readChannels();
void shiftChannels();
void test();
private:
// pin settings
int pinChannelA;
int pinChannelAQ;
int pinChannelB;
int pinChannelBQ;
// pin settings
int pinChannelA;
int pinChannelAQ;
int pinChannelB;
int pinChannelBQ;
// channels
bool prvValChannelA;
bool prvValChannelB;
bool curValChannelA;
bool curValChannelB;
// channels
bool prvValChannelA;
bool prvValChannelB;
bool curValChannelA;
bool curValChannelB;
bool readChannelA;
bool readChannelAQ;
bool readChannelB;
bool readChannelBQ;
// encoder
long position;
int scalingFactor;
int encoderType;
bool readChannelA;
bool readChannelAQ;
bool readChannelB;
bool readChannelBQ;
// encoder
long position;
int scalingFactor;
int encoderType;
};
#endif /* STEPPERCONTROLENCODER_H_ */

View File

@ -8,15 +8,15 @@
* Modified again, June 2014 by Paul Stoffregen
*
* This is free software. You can redistribute it and/or modify it under
* the terms of Creative Commons Attribution 3.0 United States License.
* To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/
* the terms of Creative Commons Attribution 3.0 United States License.
* To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/
* or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA.
*
*/
#include "TimerOne.h"
TimerOne Timer1; // preinstatiate
TimerOne Timer1; // preinstatiate
unsigned short TimerOne::pwmPeriod = 0;
unsigned char TimerOne::clockSelectBits = 0;
@ -33,11 +33,13 @@ ISR(TIMER1_OVF_vect)
void ftm1_isr(void)
{
uint32_t sc = FTM1_SC;
#ifdef KINETISL
if (sc & 0x80) FTM1_SC = sc;
#else
if (sc & 0x80) FTM1_SC = sc & 0x7F;
#endif
#ifdef KINETISL
if (sc & 0x80)
FTM1_SC = sc;
#else
if (sc & 0x80)
FTM1_SC = sc & 0x7F;
#endif
Timer1.isrCallback();
}

View File

@ -5,11 +5,11 @@
* Modified June 2009 by Michael Polli and Jesse Tane to fix a bug in setPeriod() which caused the timer to stop
* Modified April 2012 by Paul Stoffregen - portable to other AVR chips, use inline functions
* Modified again, June 2014 by Paul Stoffregen - support Teensy 3.x & even more AVR chips
*
*
*
* This is free software. You can redistribute it and/or modify it under
* the terms of Creative Commons Attribution 3.0 United States License.
* To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/
* the terms of Creative Commons Attribution 3.0 United States License.
* To view a copy of this license, visit http://creativecommons.org/licenses/by/3.0/us/
* or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA.
*
*/
@ -25,273 +25,339 @@
#include "known_16bit_timers.h"
#define TIMER1_RESOLUTION 65536UL // Timer1 is 16 bit
#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)) {
TCCR1B = _BV(WGM13); // set mode as phase and frequency correct pwm, stop the timer
TCCR1A = 0; // clear control register A
setPeriod(microseconds);
public:
//****************************
// Configuration
//****************************
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))
{
const unsigned long cycles = (F_CPU / 2000000) * microseconds;
if (cycles < TIMER1_RESOLUTION)
{
clockSelectBits = _BV(CS10);
pwmPeriod = cycles;
}
void setPeriod(unsigned long microseconds) __attribute__((always_inline)) {
const unsigned long cycles = (F_CPU / 2000000) * microseconds;
if (cycles < TIMER1_RESOLUTION) {
clockSelectBits = _BV(CS10);
pwmPeriod = cycles;
} else
if (cycles < TIMER1_RESOLUTION * 8) {
clockSelectBits = _BV(CS11);
pwmPeriod = cycles / 8;
} else
if (cycles < TIMER1_RESOLUTION * 64) {
clockSelectBits = _BV(CS11) | _BV(CS10);
pwmPeriod = cycles / 64;
} else
if (cycles < TIMER1_RESOLUTION * 256) {
clockSelectBits = _BV(CS12);
pwmPeriod = cycles / 256;
} else
if (cycles < TIMER1_RESOLUTION * 1024) {
clockSelectBits = _BV(CS12) | _BV(CS10);
pwmPeriod = cycles / 1024;
} else {
clockSelectBits = _BV(CS12) | _BV(CS10);
pwmPeriod = TIMER1_RESOLUTION - 1;
}
ICR1 = pwmPeriod;
TCCR1B = _BV(WGM13) | clockSelectBits;
else if (cycles < TIMER1_RESOLUTION * 8)
{
clockSelectBits = _BV(CS11);
pwmPeriod = cycles / 8;
}
else if (cycles < TIMER1_RESOLUTION * 64)
{
clockSelectBits = _BV(CS11) | _BV(CS10);
pwmPeriod = cycles / 64;
}
else if (cycles < TIMER1_RESOLUTION * 256)
{
clockSelectBits = _BV(CS12);
pwmPeriod = cycles / 256;
}
else if (cycles < TIMER1_RESOLUTION * 1024)
{
clockSelectBits = _BV(CS12) | _BV(CS10);
pwmPeriod = cycles / 1024;
}
else
{
clockSelectBits = _BV(CS12) | _BV(CS10);
pwmPeriod = TIMER1_RESOLUTION - 1;
}
ICR1 = pwmPeriod;
TCCR1B = _BV(WGM13) | clockSelectBits;
}
//****************************
// Run Control
//****************************
void start() __attribute__((always_inline)) {
TCCR1B = 0;
TCNT1 = 0; // TODO: does this cause an undesired interrupt?
resume();
}
void stop() __attribute__((always_inline)) {
TCCR1B = _BV(WGM13);
}
void restart() __attribute__((always_inline)) {
start();
}
void resume() __attribute__((always_inline)) {
TCCR1B = _BV(WGM13) | clockSelectBits;
}
//****************************
// Run Control
//****************************
void start() __attribute__((always_inline))
{
TCCR1B = 0;
TCNT1 = 0; // TODO: does this cause an undesired interrupt?
resume();
}
void stop() __attribute__((always_inline))
{
TCCR1B = _BV(WGM13);
}
void restart() __attribute__((always_inline))
{
start();
}
void resume() __attribute__((always_inline))
{
TCCR1B = _BV(WGM13) | clockSelectBits;
}
//****************************
// PWM outputs
//****************************
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;
#ifdef TIMER1_B_PIN
else if (pin == TIMER1_B_PIN) OCR1B = dutyCycle;
#endif
#ifdef TIMER1_C_PIN
else if (pin == TIMER1_C_PIN) OCR1C = dutyCycle;
#endif
//****************************
// PWM outputs
//****************************
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;
#ifdef TIMER1_B_PIN
else if (pin == TIMER1_B_PIN)
OCR1B = dutyCycle;
#endif
#ifdef TIMER1_C_PIN
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); }
#endif
#ifdef TIMER1_C_PIN
else if (pin == TIMER1_C_PIN) { pinMode(TIMER1_C_PIN, OUTPUT); TCCR1A |= _BV(COM1C1); }
#endif
setPwmDuty(pin, duty);
TCCR1B = _BV(WGM13) | clockSelectBits;
#ifdef TIMER1_B_PIN
else if (pin == TIMER1_B_PIN)
{
pinMode(TIMER1_B_PIN, OUTPUT);
TCCR1A |= _BV(COM1B1);
}
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);
#ifdef TIMER1_B_PIN
else if (pin == TIMER1_B_PIN) TCCR1A &= ~_BV(COM1B1);
#endif
#ifdef TIMER1_C_PIN
else if (pin == TIMER1_C_PIN) TCCR1A &= ~_BV(COM1C1);
#endif
#endif
#ifdef TIMER1_C_PIN
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);
pwm(pin, duty);
}
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);
#endif
#ifdef TIMER1_C_PIN
else if (pin == TIMER1_C_PIN)
TCCR1A &= ~_BV(COM1C1);
#endif
}
//****************************
// Interrupt Function
//****************************
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);
attachInterrupt(isr);
}
void detachInterrupt() __attribute__((always_inline)) {
TIMSK1 = 0;
}
static void (*isrCallback)();
private:
// properties
static unsigned short pwmPeriod;
static unsigned char clockSelectBits;
//****************************
// Interrupt Function
//****************************
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);
attachInterrupt(isr);
}
void detachInterrupt() __attribute__((always_inline))
{
TIMSK1 = 0;
}
static void (*isrCallback)();
private:
// properties
static unsigned short pwmPeriod;
static unsigned char clockSelectBits;
#elif defined(__arm__) && defined(CORE_TEENSY)
#if defined(KINETISK)
#define F_TIMER F_BUS
#elif defined(KINETISL)
#define F_TIMER (F_PLL/2)
#define F_TIMER (F_PLL / 2)
#endif
public:
//****************************
// Configuration
//****************************
void initialize(unsigned long microseconds=1000000) __attribute__((always_inline)) {
setPeriod(microseconds);
public:
//****************************
// Configuration
//****************************
void initialize(unsigned long microseconds = 1000000) __attribute__((always_inline))
{
setPeriod(microseconds);
}
void setPeriod(unsigned long microseconds) __attribute__((always_inline))
{
const unsigned long cycles = (F_TIMER / 2000000) * microseconds;
if (cycles < TIMER1_RESOLUTION)
{
clockSelectBits = 0;
pwmPeriod = cycles;
}
void setPeriod(unsigned long microseconds) __attribute__((always_inline)) {
const unsigned long cycles = (F_TIMER / 2000000) * microseconds;
if (cycles < TIMER1_RESOLUTION) {
clockSelectBits = 0;
pwmPeriod = cycles;
} else
if (cycles < TIMER1_RESOLUTION * 2) {
clockSelectBits = 1;
pwmPeriod = cycles >> 1;
} else
if (cycles < TIMER1_RESOLUTION * 4) {
clockSelectBits = 2;
pwmPeriod = cycles >> 2;
} else
if (cycles < TIMER1_RESOLUTION * 8) {
clockSelectBits = 3;
pwmPeriod = cycles >> 3;
} else
if (cycles < TIMER1_RESOLUTION * 16) {
clockSelectBits = 4;
pwmPeriod = cycles >> 4;
} else
if (cycles < TIMER1_RESOLUTION * 32) {
clockSelectBits = 5;
pwmPeriod = cycles >> 5;
} else
if (cycles < TIMER1_RESOLUTION * 64) {
clockSelectBits = 6;
pwmPeriod = cycles >> 6;
} else
if (cycles < TIMER1_RESOLUTION * 128) {
clockSelectBits = 7;
pwmPeriod = cycles >> 7;
} else {
clockSelectBits = 7;
pwmPeriod = TIMER1_RESOLUTION - 1;
}
uint32_t sc = FTM1_SC;
FTM1_SC = 0;
FTM1_MOD = pwmPeriod;
FTM1_SC = FTM_SC_CLKS(1) | FTM_SC_CPWMS | clockSelectBits | (sc & FTM_SC_TOIE);
else if (cycles < TIMER1_RESOLUTION * 2)
{
clockSelectBits = 1;
pwmPeriod = cycles >> 1;
}
else if (cycles < TIMER1_RESOLUTION * 4)
{
clockSelectBits = 2;
pwmPeriod = cycles >> 2;
}
else if (cycles < TIMER1_RESOLUTION * 8)
{
clockSelectBits = 3;
pwmPeriod = cycles >> 3;
}
else if (cycles < TIMER1_RESOLUTION * 16)
{
clockSelectBits = 4;
pwmPeriod = cycles >> 4;
}
else if (cycles < TIMER1_RESOLUTION * 32)
{
clockSelectBits = 5;
pwmPeriod = cycles >> 5;
}
else if (cycles < TIMER1_RESOLUTION * 64)
{
clockSelectBits = 6;
pwmPeriod = cycles >> 6;
}
else if (cycles < TIMER1_RESOLUTION * 128)
{
clockSelectBits = 7;
pwmPeriod = cycles >> 7;
}
else
{
clockSelectBits = 7;
pwmPeriod = TIMER1_RESOLUTION - 1;
}
uint32_t sc = FTM1_SC;
FTM1_SC = 0;
FTM1_MOD = pwmPeriod;
FTM1_SC = FTM_SC_CLKS(1) | FTM_SC_CPWMS | clockSelectBits | (sc & FTM_SC_TOIE);
}
//****************************
// Run Control
//****************************
void start() __attribute__((always_inline)) {
stop();
FTM1_CNT = 0;
resume();
}
void stop() __attribute__((always_inline)) {
FTM1_SC = FTM1_SC & (FTM_SC_TOIE | FTM_SC_CPWMS | FTM_SC_PS(7));
}
void restart() __attribute__((always_inline)) {
start();
}
void resume() __attribute__((always_inline)) {
FTM1_SC = (FTM1_SC & (FTM_SC_TOIE | FTM_SC_PS(7))) | FTM_SC_CPWMS | FTM_SC_CLKS(1);
}
//****************************
// Run Control
//****************************
void start() __attribute__((always_inline))
{
stop();
FTM1_CNT = 0;
resume();
}
void stop() __attribute__((always_inline))
{
FTM1_SC = FTM1_SC & (FTM_SC_TOIE | FTM_SC_CPWMS | FTM_SC_PS(7));
}
void restart() __attribute__((always_inline))
{
start();
}
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)) {
unsigned long dutyCycle = pwmPeriod;
dutyCycle *= duty;
dutyCycle >>= 10;
if (pin == TIMER1_A_PIN) {
FTM1_C0V = dutyCycle;
} else if (pin == TIMER1_B_PIN) {
FTM1_C1V = dutyCycle;
}
//****************************
// PWM outputs
//****************************
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline))
{
unsigned long dutyCycle = pwmPeriod;
dutyCycle *= duty;
dutyCycle >>= 10;
if (pin == TIMER1_A_PIN)
{
FTM1_C0V = dutyCycle;
}
void pwm(char pin, unsigned int duty) __attribute__((always_inline)) {
setPwmDuty(pin, duty);
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) {
*portConfigRegister(TIMER1_B_PIN) = PORT_PCR_MUX(3) | PORT_PCR_DSE | PORT_PCR_SRE;
}
else if (pin == TIMER1_B_PIN)
{
FTM1_C1V = dutyCycle;
}
void pwm(char pin, unsigned int duty, unsigned long microseconds) __attribute__((always_inline)) {
if (microseconds > 0) setPeriod(microseconds);
pwm(pin, duty);
}
void pwm(char pin, unsigned int duty) __attribute__((always_inline))
{
setPwmDuty(pin, duty);
if (pin == TIMER1_A_PIN)
{
*portConfigRegister(TIMER1_A_PIN) = PORT_PCR_MUX(3) | PORT_PCR_DSE | PORT_PCR_SRE;
}
void disablePwm(char pin) __attribute__((always_inline)) {
if (pin == TIMER1_A_PIN) {
*portConfigRegister(TIMER1_A_PIN) = 0;
} else if (pin == TIMER1_B_PIN) {
*portConfigRegister(TIMER1_B_PIN) = 0;
}
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);
pwm(pin, duty);
}
void disablePwm(char pin) __attribute__((always_inline))
{
if (pin == TIMER1_A_PIN)
{
*portConfigRegister(TIMER1_A_PIN) = 0;
}
else if (pin == TIMER1_B_PIN)
{
*portConfigRegister(TIMER1_B_PIN) = 0;
}
}
//****************************
// Interrupt Function
//****************************
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);
attachInterrupt(isr);
}
void detachInterrupt() __attribute__((always_inline)) {
FTM1_SC &= ~FTM_SC_TOIE;
NVIC_DISABLE_IRQ(IRQ_FTM1);
}
static void (*isrCallback)();
//****************************
// Interrupt Function
//****************************
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);
attachInterrupt(isr);
}
void detachInterrupt() __attribute__((always_inline))
{
FTM1_SC &= ~FTM_SC_TOIE;
NVIC_DISABLE_IRQ(IRQ_FTM1);
}
static void (*isrCallback)();
private:
// properties
static unsigned short pwmPeriod;
static unsigned char clockSelectBits;
private:
// properties
static unsigned short pwmPeriod;
static unsigned char clockSelectBits;
#undef F_TIMER
@ -301,4 +367,3 @@ class TimerOne
extern TimerOne Timer1;
#endif

View File

@ -8,9 +8,8 @@
#include "TimerOne.h"
#include "MemoryFree.h"
static char commandEndChar = 0x0A;
static GCodeProcessor* gCodeProcessor = new GCodeProcessor();
static GCodeProcessor *gCodeProcessor = new GCodeProcessor();
unsigned long lastAction;
unsigned long currentTime;
@ -25,9 +24,10 @@ int incomingCommandPointer = 0;
// Blink led routine used for testing
bool blink = false;
void blinkLed() {
blink = !blink;
digitalWrite(LED_PIN,blink);
void blinkLed()
{
blink = !blink;
digitalWrite(LED_PIN, blink);
}
// Interrupt handling for:
@ -37,208 +37,218 @@ void blinkLed() {
//
bool interruptBusy = false;
int interruptSecondTimer = 0;
void interrupt(void) {
interruptSecondTimer++;
void interrupt(void)
{
interruptSecondTimer++;
if (interruptBusy == false) {
if (interruptBusy == false)
{
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
interruptBusy = true;
StepperControl::getInstance()->handleMovementInterrupt();
// Check the actions triggered once per second
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED) {
interruptSecondTimer = 0;
PinGuard::getInstance()->checkPins();
//blinkLed();
}
// Check the actions triggered once per second
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED)
{
interruptSecondTimer = 0;
PinGuard::getInstance()->checkPins();
//blinkLed();
}
interruptBusy = false;
}
interruptBusy = false;
}
}
//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);
pinMode(X_DIR_PIN , OUTPUT);
pinMode(X_ENABLE_PIN, OUTPUT);
pinMode(E_STEP_PIN , OUTPUT);
pinMode(E_DIR_PIN , OUTPUT);
pinMode(E_ENABLE_PIN, OUTPUT);
pinMode(X_MIN_PIN , INPUT_PULLUP );
pinMode(X_MAX_PIN , INPUT_PULLUP );
// Setup pin input/output settings
pinMode(X_STEP_PIN, OUTPUT);
pinMode(X_DIR_PIN, OUTPUT);
pinMode(X_ENABLE_PIN, OUTPUT);
pinMode(E_STEP_PIN, OUTPUT);
pinMode(E_DIR_PIN, OUTPUT);
pinMode(E_ENABLE_PIN, OUTPUT);
pinMode(X_MIN_PIN, INPUT_PULLUP);
pinMode(X_MAX_PIN, INPUT_PULLUP);
pinMode(Y_STEP_PIN , OUTPUT);
pinMode(Y_DIR_PIN , OUTPUT);
pinMode(Y_ENABLE_PIN, OUTPUT);
pinMode(Y_MIN_PIN , INPUT_PULLUP );
pinMode(Y_MAX_PIN , INPUT_PULLUP );
pinMode(Y_STEP_PIN, OUTPUT);
pinMode(Y_DIR_PIN, OUTPUT);
pinMode(Y_ENABLE_PIN, OUTPUT);
pinMode(Y_MIN_PIN, INPUT_PULLUP);
pinMode(Y_MAX_PIN, INPUT_PULLUP);
pinMode(Z_STEP_PIN , OUTPUT);
pinMode(Z_DIR_PIN , OUTPUT);
pinMode(Z_ENABLE_PIN, OUTPUT);
pinMode(Z_MIN_PIN , INPUT_PULLUP );
pinMode(Z_MAX_PIN , INPUT_PULLUP );
pinMode(Z_STEP_PIN, OUTPUT);
pinMode(Z_DIR_PIN, OUTPUT);
pinMode(Z_ENABLE_PIN, OUTPUT);
pinMode(Z_MIN_PIN, INPUT_PULLUP);
pinMode(Z_MAX_PIN, INPUT_PULLUP);
pinMode(HEATER_0_PIN, OUTPUT);
pinMode(HEATER_1_PIN, OUTPUT);
pinMode(FAN_PIN , OUTPUT);
pinMode(LED_PIN , OUTPUT);
pinMode(HEATER_0_PIN, OUTPUT);
pinMode(HEATER_1_PIN, OUTPUT);
pinMode(FAN_PIN, OUTPUT);
pinMode(LED_PIN, OUTPUT);
//pinMode(SERVO_0_PIN , OUTPUT);
//pinMode(SERVO_1_PIN , OUTPUT);
//pinMode(SERVO_0_PIN , OUTPUT);
//pinMode(SERVO_1_PIN , OUTPUT);
digitalWrite(X_ENABLE_PIN, HIGH);
digitalWrite(E_ENABLE_PIN, HIGH);
digitalWrite(Y_ENABLE_PIN, HIGH);
digitalWrite(Z_ENABLE_PIN, HIGH);
digitalWrite(X_ENABLE_PIN, HIGH);
digitalWrite(E_ENABLE_PIN, HIGH);
digitalWrite(Y_ENABLE_PIN, HIGH);
digitalWrite(Z_ENABLE_PIN, HIGH);
Serial.begin(115200);
Serial.begin(115200);
delay(100);
delay(100);
// Start the motor handling
//ServoControl::getInstance()->attach();
// Start the motor handling
//ServoControl::getInstance()->attach();
// Dump all values to the serial interface
ParameterList::getInstance()->readAllValues();
// Dump all values to the serial interface
ParameterList::getInstance()->readAllValues();
// Get the settings for the pin guard
PinGuard::getInstance()->loadConfig();
// Get the settings for the pin guard
PinGuard::getInstance()->loadConfig();
// Start the interrupt used for moving
// Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds
// Start the interrupt used for moving
// Interrupt management code library written by Paul Stoffregen
// The default time 100 micro seconds
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
Timer1.attachInterrupt(interrupt);
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
Timer1.start();
// Initialize the inactivity check
lastAction = millis();
// Initialize the inactivity check
lastAction = millis();
}
// 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();
// Save current time stamp for timeout actions
lastAction = millis();
// Get the input and start processing on receiving 'new line'
incomingChar = Serial.read();
incomingCommandArray[incomingCommandPointer] = incomingChar;
incomingCommandPointer++;
// Get the input and start processing on receiving 'new line'
incomingChar = Serial.read();
incomingCommandArray[incomingCommandPointer] = incomingChar;
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) {
incomingChar = '\n';
incomingCommandArray[incomingCommandPointer] = incomingChar;
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)
{
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);
//char commandChar[currentCommand.length()];
//currentCommand.toCharArray(commandChar, currentCommand.length());
//commandString += incomingChar;
//String commandString = Serial.readStringUntil(commandEndChar);
//char commandChar[currentCommand.length()];
//currentCommand.toCharArray(commandChar, currentCommand.length());
char commandChar[incomingCommandPointer + 1];
for (int i = 0; i < incomingCommandPointer -1; i++) {
commandChar[i] = incomingCommandArray[i];
}
commandChar[incomingCommandPointer] = 0;
char commandChar[incomingCommandPointer + 1];
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
// string to the command object
// Copy the command to another string object.
// because there are issues with passing the
// string to the command object
// Create a command and let it execute
//Command* command = new Command(commandString);
Command *command = new Command(commandChar);
// Create a command and let it execute
//Command* command = new Command(commandString);
Command* command = new Command(commandChar);
if (LOGGING)
{
command->print();
}
if(LOGGING) {
command->print();
}
gCodeProcessor->execute(command);
gCodeProcessor->execute(command);
free(command);
}
free(command);
}
incomingCommandPointer = 0;
}
}
incomingCommandPointer = 0;
}
}
//StepperControl::getInstance()->test();
//StepperControl::getInstance()->test();
// Check if parameters are changes, and if so load the new settings
// Check if parameters are changes, and if so load the new settings
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber())
{
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber()) {
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" loading parameters ");
CurrentState::getInstance()->printQAndNewLine();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" loading parameters ");
CurrentState::getInstance()->printQAndNewLine();
StepperControl::getInstance()->loadSettings();
PinGuard::getInstance()->loadConfig();
}
StepperControl::getInstance()->loadSettings();
PinGuard::getInstance()->loadConfig();
}
// Do periodic checks and feedback
currentTime = millis();
if (currentTime < lastAction)
{
// Do periodic checks and feedback
// If the device timer overruns, reset the idle counter
lastAction = millis();
}
else
{
currentTime = millis();
if (currentTime < lastAction) {
if ((currentTime - lastAction) > 5000)
{
// After an idle time, send the idle message
// If the device timer overruns, reset the idle counter
lastAction = millis();
}
else {
Serial.print(COMM_REPORT_CMD_IDLE);
CurrentState::getInstance()->printQAndNewLine();
if ((currentTime - lastAction) > 5000) {
// After an idle time, send the idle message
StepperControl::getInstance()->storePosition();
CurrentState::getInstance()->printPosition();
Serial.print(COMM_REPORT_CMD_IDLE);
CurrentState::getInstance()->printQAndNewLine();
CurrentState::getInstance()->storeEndStops();
CurrentState::getInstance()->printEndStops();
StepperControl::getInstance()->storePosition();
CurrentState::getInstance()->printPosition();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" MEM ");
Serial.print(freeMemory());
CurrentState::getInstance()->printQAndNewLine();
CurrentState::getInstance()->storeEndStops();
CurrentState::getInstance()->printEndStops();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" Cycle ");
Serial.print(cycleCounter);
CurrentState::getInstance()->printQAndNewLine();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" MEM ");
Serial.print(freeMemory());
CurrentState::getInstance()->printQAndNewLine();
StepperControl::getInstance()->test();
Serial.print(COMM_REPORT_COMMENT);
Serial.print(" Cycle ");
Serial.print(cycleCounter);
CurrentState::getInstance()->printQAndNewLine();
//ParameterList::getInstance()->readAllValues();
StepperControl::getInstance()->test();
//StepperControl::getInstance()->test();
//ParameterList::getInstance()->readAllValues();
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
// Serial.print(COMM_REPORT_NO_CONFIG);
// }
//StepperControl::getInstance()->test();
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
// Serial.print(COMM_REPORT_NO_CONFIG);
// }
cycleCounter++;
lastAction = millis();
}
}
cycleCounter++;
lastAction = millis();
}
}
}

View File

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

View File

@ -4,139 +4,139 @@
// Wiring-S
//
#if defined(__AVR_ATmega644P__) && defined(WIRING)
#define TIMER1_A_PIN 5
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 6
#define TIMER1_A_PIN 5
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 6
// Teensy 2.0
//
#elif defined(__AVR_ATmega32U4__) && defined(CORE_TEENSY)
#define TIMER1_A_PIN 14
#define TIMER1_B_PIN 15
#define TIMER1_C_PIN 4
#define TIMER1_ICP_PIN 22
#define TIMER1_CLK_PIN 11
#define TIMER3_A_PIN 9
#define TIMER3_ICP_PIN 10
#define TIMER1_A_PIN 14
#define TIMER1_B_PIN 15
#define TIMER1_C_PIN 4
#define TIMER1_ICP_PIN 22
#define TIMER1_CLK_PIN 11
#define TIMER3_A_PIN 9
#define TIMER3_ICP_PIN 10
// Teensy++ 2.0
#elif defined(__AVR_AT90USB1286__) && defined(CORE_TEENSY)
#define TIMER1_A_PIN 25
#define TIMER1_B_PIN 26
#define TIMER1_C_PIN 27
#define TIMER1_ICP_PIN 4
#define TIMER1_CLK_PIN 6
#define TIMER3_A_PIN 16
#define TIMER3_B_PIN 15
#define TIMER3_C_PIN 14
#define TIMER3_ICP_PIN 17
#define TIMER3_CLK_PIN 13
#define TIMER1_A_PIN 25
#define TIMER1_B_PIN 26
#define TIMER1_C_PIN 27
#define TIMER1_ICP_PIN 4
#define TIMER1_CLK_PIN 6
#define TIMER3_A_PIN 16
#define TIMER3_B_PIN 15
#define TIMER3_C_PIN 14
#define TIMER3_ICP_PIN 17
#define TIMER3_CLK_PIN 13
// Teensy 3.0
//
#elif defined(__MK20DX128__)
#define TIMER1_A_PIN 3
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 4
#define TIMER1_A_PIN 3
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 4
// Teensy 3.1
//
#elif defined(__MK20DX256__)
#define TIMER1_A_PIN 3
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 4
#define TIMER3_A_PIN 32
#define TIMER3_B_PIN 25
#define TIMER3_ICP_PIN 32
#define TIMER1_A_PIN 3
#define TIMER1_B_PIN 4
#define TIMER1_ICP_PIN 4
#define TIMER3_A_PIN 32
#define TIMER3_B_PIN 25
#define TIMER3_ICP_PIN 32
// Teensy-LC
//
#elif defined(__MKL26Z64__)
#define TIMER1_A_PIN 16
#define TIMER1_B_PIN 17
#define TIMER1_ICP_PIN 17
#define TIMER3_A_PIN 3
#define TIMER3_B_PIN 4
#define TIMER3_ICP_PIN 4
#define TIMER1_A_PIN 16
#define TIMER1_B_PIN 17
#define TIMER1_ICP_PIN 17
#define TIMER3_A_PIN 3
#define TIMER3_B_PIN 4
#define TIMER3_ICP_PIN 4
// Arduino Mega
//
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#define TIMER1_A_PIN 11
#define TIMER1_B_PIN 12
#define TIMER1_C_PIN 13
#define TIMER3_A_PIN 5
#define TIMER3_B_PIN 2
#define TIMER3_C_PIN 3
#define TIMER4_A_PIN 6
#define TIMER4_B_PIN 7
#define TIMER4_C_PIN 8
#define TIMER4_ICP_PIN 49
#define TIMER5_A_PIN 46
#define TIMER5_B_PIN 45
#define TIMER5_C_PIN 44
#define TIMER3_ICP_PIN 48
#define TIMER3_CLK_PIN 47
#define TIMER1_A_PIN 11
#define TIMER1_B_PIN 12
#define TIMER1_C_PIN 13
#define TIMER3_A_PIN 5
#define TIMER3_B_PIN 2
#define TIMER3_C_PIN 3
#define TIMER4_A_PIN 6
#define TIMER4_B_PIN 7
#define TIMER4_C_PIN 8
#define TIMER4_ICP_PIN 49
#define TIMER5_A_PIN 46
#define TIMER5_B_PIN 45
#define TIMER5_C_PIN 44
#define TIMER3_ICP_PIN 48
#define TIMER3_CLK_PIN 47
// Arduino Leonardo, Yun, etc
//
#elif defined(__AVR_ATmega32U4__)
#define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10
#define TIMER1_C_PIN 11
#define TIMER1_ICP_PIN 4
#define TIMER1_CLK_PIN 12
#define TIMER3_A_PIN 5
#define TIMER3_ICP_PIN 13
#define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10
#define TIMER1_C_PIN 11
#define TIMER1_ICP_PIN 4
#define TIMER1_CLK_PIN 12
#define TIMER3_A_PIN 5
#define TIMER3_ICP_PIN 13
// Uno, Duemilanove, LilyPad, etc
//
#elif defined (__AVR_ATmega168__) || defined (__AVR_ATmega328P__)
#define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10
#define TIMER1_ICP_PIN 8
#define TIMER1_CLK_PIN 5
#elif defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__)
#define TIMER1_A_PIN 9
#define TIMER1_B_PIN 10
#define TIMER1_ICP_PIN 8
#define TIMER1_CLK_PIN 5
// Sanguino
//
#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__)
#define TIMER1_A_PIN 13
#define TIMER1_B_PIN 12
#define TIMER1_ICP_PIN 14
#define TIMER1_CLK_PIN 1
#define TIMER1_A_PIN 13
#define TIMER1_B_PIN 12
#define TIMER1_ICP_PIN 14
#define TIMER1_CLK_PIN 1
// Wildfire - Wicked Devices
//
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION >= 3
#define TIMER1_A_PIN 5 // PD5
#define TIMER1_B_PIN 8 // PD4
#define TIMER1_ICP_PIN 6 // PD6
#define TIMER1_CLK_PIN 23 // PB1
#define TIMER3_A_PIN 12 // PB6
#define TIMER3_B_PIN 13 // PB7
#define TIMER3_ICP_PIN 9 // PB5
#define TIMER3_CLK_PIN 0 // PD0
#define TIMER1_A_PIN 5 // PD5
#define TIMER1_B_PIN 8 // PD4
#define TIMER1_ICP_PIN 6 // PD6
#define TIMER1_CLK_PIN 23 // PB1
#define TIMER3_A_PIN 12 // PB6
#define TIMER3_B_PIN 13 // PB7
#define TIMER3_ICP_PIN 9 // PB5
#define TIMER3_CLK_PIN 0 // PD0
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION < 3
#define TIMER1_A_PIN 5 // PD5
#define TIMER1_B_PIN 4 // PD4
#define TIMER1_ICP_PIN 6 // PD6
#define TIMER1_CLK_PIN 15 // PB1
#define TIMER3_A_PIN 12 // PB6
#define TIMER3_B_PIN 13 // PB7
#define TIMER3_ICP_PIN 11 // PB5
#define TIMER3_CLK_PIN 0 // PD0
#define TIMER1_A_PIN 5 // PD5
#define TIMER1_B_PIN 4 // PD4
#define TIMER1_ICP_PIN 6 // PD6
#define TIMER1_CLK_PIN 15 // PB1
#define TIMER3_A_PIN 12 // PB6
#define TIMER3_B_PIN 13 // PB7
#define TIMER3_ICP_PIN 11 // PB5
#define TIMER3_CLK_PIN 0 // PD0
// Mighty-1284 - Maniacbug
//
#elif defined(__AVR_ATmega1284P__)
#define TIMER1_A_PIN 12 // PD5
#define TIMER1_B_PIN 13 // PD4
#define TIMER1_ICP_PIN 14 // PD6
#define TIMER1_CLK_PIN 1 // PB1
#define TIMER3_A_PIN 6 // PB6
#define TIMER3_B_PIN 7 // PB7
#define TIMER3_ICP_PIN 5 // PB5
#define TIMER3_CLK_PIN 8 // PD0
#define TIMER1_A_PIN 12 // PD5
#define TIMER1_B_PIN 13 // PD4
#define TIMER1_ICP_PIN 14 // PD6
#define TIMER1_CLK_PIN 1 // PB1
#define TIMER3_A_PIN 6 // PB6
#define TIMER3_B_PIN 7 // PB7
#define TIMER3_ICP_PIN 5 // PB5
#define TIMER3_CLK_PIN 8 // PD0
#endif

View File

@ -1,52 +1,52 @@
// For RAMPS 1.4
#define X_STEP_PIN 54
#define X_DIR_PIN 55
#define X_ENABLE_PIN 38
#define X_MIN_PIN 3
#define X_MAX_PIN 2
#define X_ENCDR_A 16
#define X_ENCDR_B 17
#define X_ENCDR_A_Q 31
#define X_ENCDR_B_Q 33
#define X_STEP_PIN 54
#define X_DIR_PIN 55
#define X_ENABLE_PIN 38
#define X_MIN_PIN 3
#define X_MAX_PIN 2
#define X_ENCDR_A 16
#define X_ENCDR_B 17
#define X_ENCDR_A_Q 31
#define X_ENCDR_B_Q 33
#define Y_STEP_PIN 60
#define Y_DIR_PIN 61
#define Y_ENABLE_PIN 56
#define Y_MIN_PIN 14
#define Y_MAX_PIN 15
#define Y_ENCDR_A 23
#define Y_ENCDR_B 25
#define Y_ENCDR_A_Q 35
#define Y_ENCDR_B_Q 37
#define Y_STEP_PIN 60
#define Y_DIR_PIN 61
#define Y_ENABLE_PIN 56
#define Y_MIN_PIN 14
#define Y_MAX_PIN 15
#define Y_ENCDR_A 23
#define Y_ENCDR_B 25
#define Y_ENCDR_A_Q 35
#define Y_ENCDR_B_Q 37
#define Z_STEP_PIN 46
#define Z_DIR_PIN 48
#define Z_ENABLE_PIN 62
#define Z_MIN_PIN 18
#define Z_MAX_PIN 19
#define Z_ENCDR_A 27
#define Z_ENCDR_B 29
#define Z_ENCDR_A_Q 39
#define Z_ENCDR_B_Q 41
#define Z_STEP_PIN 46
#define Z_DIR_PIN 48
#define Z_ENABLE_PIN 62
#define Z_MIN_PIN 18
#define Z_MAX_PIN 19
#define Z_ENCDR_A 27
#define Z_ENCDR_B 29
#define Z_ENCDR_A_Q 39
#define Z_ENCDR_B_Q 41
#define E_STEP_PIN 26
#define E_DIR_PIN 28
#define E_ENABLE_PIN 24
#define E_STEP_PIN 26
#define E_DIR_PIN 28
#define E_ENABLE_PIN 24
#define SDPOWER -1
#define SDSS 53
#define LED_PIN 13
#define SDPOWER -1
#define SDSS 53
#define LED_PIN 13
#define FAN_PIN 9
#define FAN_PIN 9
#define PS_ON_PIN 12
#define KILL_PIN -1
#define PS_ON_PIN 12
#define KILL_PIN -1
#define HEATER_0_PIN 10
#define HEATER_1_PIN 8
#define TEMP_0_PIN 13 // ANALOG NUMBERING
#define TEMP_1_PIN 14 // ANALOG NUMBERING
#define HEATER_0_PIN 10
#define HEATER_1_PIN 8
#define TEMP_0_PIN 13 // ANALOG NUMBERING
#define TEMP_1_PIN 14 // ANALOG NUMBERING
#define SERVO_0_PIN 4
#define SERVO_1_PIN 5
#define SERVO_0_PIN 4
#define SERVO_1_PIN 5

View File

@ -1 +1 @@
// All code in farmbot_arduino_controller.cpp
// All code in farmbot_arduino_controller.cpp

View File

@ -173,4 +173,4 @@
<UserProperties vm.programmer_name="avrisp" arduino.upload.port="COM3" />
</VisualStudio>
</ProjectExtensions>
</Project>
</Project>

View File

@ -261,4 +261,4 @@
<Filter>Header Files</Filter>
</ClInclude>
</ItemGroup>
</Project>
</Project>