Formatting update
parent
413f5c868f
commit
3d573dca0c
|
@ -25,4 +25,4 @@
|
||||||
/.build
|
/.build
|
||||||
/.vs
|
/.vs
|
||||||
/src/Debug
|
/src/Debug
|
||||||
/src/__vm
|
/src/__vm
|
||||||
|
|
2
LICENSE
2
LICENSE
|
@ -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
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
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
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
SOFTWARE.
|
SOFTWARE.
|
||||||
|
|
12
README.md
12
README.md
|
@ -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_MAX_PIN | 2 | X axis end stop at far position
|
||||||
X_ENCDR_A | 16 | X axis encoder A channel
|
X_ENCDR_A | 16 | X axis encoder A channel
|
||||||
X_ENCDR_B | 17 | X axis encoder B 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)
|
X_ENCDR_B_Q | 33 | X axis encoder B channel for quarature (not implemented)
|
||||||
Y_STEP_PIN | 60 | Y axis step signal
|
Y_STEP_PIN | 60 | Y axis step signal
|
||||||
Y_DIR_PIN | 61 | Y axis direction choice
|
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_MAX_PIN | 15 | Y axis end stop at far position
|
||||||
Y_ENCDR_A | 23 | Y axis encoder A channel
|
Y_ENCDR_A | 23 | Y axis encoder A channel
|
||||||
Y_ENCDR_B | 25 | Y axis encoder B 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_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_B_Q | 37 | Y axis encoder B channel for quarature (not implemented)
|
||||||
Z_STEP_PIN | 46 | Z axis step signal
|
Z_STEP_PIN | 46 | Z axis step signal
|
||||||
Z_DIR_PIN | 48 | Z axis direction choice
|
Z_DIR_PIN | 48 | Z axis direction choice
|
||||||
Z_ENABLE_PIN | 62 | Z axis enable
|
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_MAX_PIN | 19 | Z axis end stop at far position
|
||||||
Z_ENCDR_A | 27 | Z axis encoder A channel
|
Z_ENCDR_A | 27 | Z axis encoder A channel
|
||||||
Z_ENCDR_B | 29 | Z axis encoder B 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_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_B_Q | 41 | Z axis encoder B channel for quarature (not implemented)
|
||||||
LED_PIN | 13 | on board LED
|
LED_PIN | 13 | on board LED
|
||||||
FAN_PIN | 9 | RAMPS board fan pin
|
FAN_PIN | 9 | RAMPS board fan pin
|
||||||
HEATER_0_PIN | 10 | RAMPS board heating pin 0
|
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 |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 |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 |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 |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 |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)
|
F |52 |E P |Read value from the tool mount with I2C (not implemented)
|
||||||
|
|
465
src/Command.cpp
465
src/Command.cpp
|
@ -1,276 +1,333 @@
|
||||||
#include "Command.h"
|
#include "Command.h"
|
||||||
|
|
||||||
const char axisCodes[3] = { 'X', 'Y', 'Z' };
|
const char axisCodes[3] = {'X', 'Y', 'Z'};
|
||||||
const char axisSpeedCodes[3] = { 'A', 'B', 'C' };
|
const char axisSpeedCodes[3] = {'A', 'B', 'C'};
|
||||||
const char speedCode = 'S';
|
const char speedCode = 'S';
|
||||||
const char parameterIdCode = 'P';
|
const char parameterIdCode = 'P';
|
||||||
const char parameterValueCode = 'V';
|
const char parameterValueCode = 'V';
|
||||||
const char parameterValue2Code= 'W';
|
const char parameterValue2Code = 'W';
|
||||||
const char elementCode = 'E';
|
const char elementCode = 'E';
|
||||||
const char timeCode = 'T';
|
const char timeCode = 'T';
|
||||||
const char modeCode = 'M';
|
const char modeCode = 'M';
|
||||||
const char msgQueueCode = 'Q';
|
const char msgQueueCode = 'Q';
|
||||||
|
|
||||||
CommandCodeEnum commandCodeEnum = CODE_UNDEFINED;
|
CommandCodeEnum commandCodeEnum = CODE_UNDEFINED;
|
||||||
|
|
||||||
Command::Command(char * commandChar) {
|
Command::Command(char *commandChar)
|
||||||
|
{
|
||||||
|
|
||||||
char * charBuf = commandChar;
|
char *charBuf = commandChar;
|
||||||
char* charPointer;
|
char *charPointer;
|
||||||
bool invalidCommand = false;
|
bool invalidCommand = false;
|
||||||
|
|
||||||
charPointer = strtok(charBuf, " \n\r");
|
charPointer = strtok(charBuf, " \n\r");
|
||||||
|
|
||||||
if (charPointer[0] == 'G' || charPointer[0] == 'F') {
|
if (charPointer[0] == 'G' || charPointer[0] == 'F')
|
||||||
commandCodeEnum = getGCodeEnum(charPointer);
|
{
|
||||||
} else {
|
commandCodeEnum = getGCodeEnum(charPointer);
|
||||||
invalidCommand = true;
|
}
|
||||||
return;
|
else
|
||||||
}
|
{
|
||||||
|
invalidCommand = true;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
while (charPointer != NULL) {
|
while (charPointer != NULL)
|
||||||
getParameter(charPointer);
|
{
|
||||||
|
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) {
|
if (strcmp(code, "F11") == 0)
|
||||||
return G00;
|
{
|
||||||
}
|
return F11;
|
||||||
if (strcmp(code, "G1") == 0 || strcmp(code, "G01") == 0) {
|
}
|
||||||
return G01;
|
if (strcmp(code, "F12") == 0)
|
||||||
}
|
{
|
||||||
//if (strcmp(code, "F3") == 0 || strcmp(code, "F03") == 0) {
|
return F12;
|
||||||
// return F03;
|
}
|
||||||
//}
|
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) {
|
if (strcmp(code, "F20") == 0)
|
||||||
return F11;
|
{
|
||||||
}
|
return F20;
|
||||||
if (strcmp(code, "F12") == 0) {
|
}
|
||||||
return F12;
|
if (strcmp(code, "F21") == 0)
|
||||||
}
|
{
|
||||||
if (strcmp(code, "F13") == 0) {
|
return F21;
|
||||||
return F13;
|
}
|
||||||
}
|
if (strcmp(code, "F22") == 0)
|
||||||
if (strcmp(code, "F14") == 0) {
|
{
|
||||||
return F14;
|
return F22;
|
||||||
}
|
}
|
||||||
if (strcmp(code, "F15") == 0) {
|
|
||||||
return F15;
|
|
||||||
}
|
|
||||||
if (strcmp(code, "F16") == 0) {
|
|
||||||
return F16;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (strcmp(code, "F20") == 0) {
|
if (strcmp(code, "F31") == 0)
|
||||||
return F20;
|
{
|
||||||
}
|
return F31;
|
||||||
if (strcmp(code, "F21") == 0) {
|
}
|
||||||
return F21;
|
if (strcmp(code, "F32") == 0)
|
||||||
}
|
{
|
||||||
if (strcmp(code, "F22") == 0) {
|
return F32;
|
||||||
return F22;
|
}
|
||||||
}
|
|
||||||
|
|
||||||
if (strcmp(code, "F31") == 0) {
|
if (strcmp(code, "F41") == 0)
|
||||||
return F31;
|
{
|
||||||
}
|
return F41;
|
||||||
if (strcmp(code, "F32") == 0) {
|
}
|
||||||
return F32;
|
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) {
|
if (strcmp(code, "F61") == 0)
|
||||||
return F41;
|
{
|
||||||
}
|
return F61;
|
||||||
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) {
|
if (strcmp(code, "F81") == 0)
|
||||||
return F61;
|
{
|
||||||
}
|
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 CODE_UNDEFINED;
|
||||||
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;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
double minusNotAllowed(double value) {
|
double minusNotAllowed(double value)
|
||||||
if(value < 0) {
|
{
|
||||||
return 0;
|
if (value < 0)
|
||||||
}
|
{
|
||||||
return value;
|
return 0;
|
||||||
|
}
|
||||||
|
return value;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Command::getParameter(char* charPointer) {
|
void Command::getParameter(char *charPointer)
|
||||||
|
{
|
||||||
|
|
||||||
//msgQueue = 24;
|
//msgQueue = 24;
|
||||||
|
|
||||||
if (charPointer[0] == axisCodes[0] ){
|
if (charPointer[0] == axisCodes[0])
|
||||||
axisValue[0] = atof(charPointer + 1 );
|
{
|
||||||
//msgQueue = 77;
|
axisValue[0] = atof(charPointer + 1);
|
||||||
}
|
//msgQueue = 77;
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == axisCodes[1] ){
|
if (charPointer[0] == axisCodes[1])
|
||||||
axisValue[1] = atof(charPointer + 1 );
|
{
|
||||||
}
|
axisValue[1] = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == axisCodes[2] ){
|
if (charPointer[0] == axisCodes[2])
|
||||||
axisValue[2] = atof(charPointer + 1 );
|
{
|
||||||
}
|
axisValue[2] = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == axisSpeedCodes[0] ){
|
if (charPointer[0] == axisSpeedCodes[0])
|
||||||
axisSpeedValue[0] = atof(charPointer + 1 );
|
{
|
||||||
}
|
axisSpeedValue[0] = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == axisSpeedCodes[1] ){
|
if (charPointer[0] == axisSpeedCodes[1])
|
||||||
axisSpeedValue[1] = atof(charPointer + 1 );
|
{
|
||||||
}
|
axisSpeedValue[1] = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == axisSpeedCodes[2] ){
|
if (charPointer[0] == axisSpeedCodes[2])
|
||||||
axisSpeedValue[2] = atof(charPointer + 1 );
|
{
|
||||||
}
|
axisSpeedValue[2] = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == speedCode ){
|
if (charPointer[0] == speedCode)
|
||||||
speedValue = atof(charPointer + 1 );
|
{
|
||||||
}
|
speedValue = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == parameterIdCode ){
|
if (charPointer[0] == parameterIdCode)
|
||||||
parameterId = atof(charPointer + 1 );
|
{
|
||||||
}
|
parameterId = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == parameterValueCode ){
|
if (charPointer[0] == parameterValueCode)
|
||||||
parameterValue = atof(charPointer + 1 );
|
{
|
||||||
|
parameterValue = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
}
|
if (charPointer[0] == parameterValue2Code)
|
||||||
|
{
|
||||||
|
parameterValue2 = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == parameterValue2Code ){
|
if (charPointer[0] == elementCode)
|
||||||
parameterValue2 = atof(charPointer + 1 );
|
{
|
||||||
}
|
element = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == elementCode ){
|
if (charPointer[0] == timeCode)
|
||||||
element = atof(charPointer + 1 );
|
{
|
||||||
}
|
time = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == timeCode ){
|
if (charPointer[0] == modeCode)
|
||||||
time = atof(charPointer + 1 );
|
{
|
||||||
}
|
mode = atof(charPointer + 1);
|
||||||
|
}
|
||||||
|
|
||||||
if (charPointer[0] == modeCode ){
|
if (charPointer[0] == msgQueueCode)
|
||||||
mode = atof(charPointer + 1 );
|
{
|
||||||
}
|
msgQueue = atof(charPointer + 1);
|
||||||
|
//msgQueue = 5;
|
||||||
if (charPointer[0] == msgQueueCode ){
|
}
|
||||||
msgQueue = atof(charPointer + 1 );
|
|
||||||
//msgQueue = 5;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void Command::print() {
|
void Command::print()
|
||||||
Serial.print("R99 Command with code: ");
|
{
|
||||||
Serial.print(commandCodeEnum);
|
Serial.print("R99 Command with code: ");
|
||||||
Serial.print(", X: ");
|
Serial.print(commandCodeEnum);
|
||||||
Serial.print(axisValue[0]);
|
Serial.print(", X: ");
|
||||||
Serial.print(", Y: ");
|
Serial.print(axisValue[0]);
|
||||||
Serial.print(axisValue[1]);
|
Serial.print(", Y: ");
|
||||||
Serial.print(", Z: ");
|
Serial.print(axisValue[1]);
|
||||||
Serial.print(axisValue[2]);
|
Serial.print(", Z: ");
|
||||||
Serial.print(", S: ");
|
Serial.print(axisValue[2]);
|
||||||
Serial.print(speedValue);
|
Serial.print(", S: ");
|
||||||
Serial.print(", P: ");
|
Serial.print(speedValue);
|
||||||
Serial.print(parameterId);
|
Serial.print(", P: ");
|
||||||
Serial.print(", V: ");
|
Serial.print(parameterId);
|
||||||
Serial.print(parameterValue);
|
Serial.print(", V: ");
|
||||||
|
Serial.print(parameterValue);
|
||||||
|
|
||||||
Serial.print(", W: ");
|
Serial.print(", W: ");
|
||||||
Serial.print(parameterValue2);
|
Serial.print(parameterValue2);
|
||||||
Serial.print(", T: ");
|
Serial.print(", T: ");
|
||||||
Serial.print(time);
|
Serial.print(time);
|
||||||
Serial.print(", E: ");
|
Serial.print(", E: ");
|
||||||
Serial.print(element);
|
Serial.print(element);
|
||||||
Serial.print(", M: ");
|
Serial.print(", M: ");
|
||||||
Serial.print(mode);
|
Serial.print(mode);
|
||||||
Serial.print(", Q: ");
|
Serial.print(", Q: ");
|
||||||
Serial.print(msgQueue);
|
Serial.print(msgQueue);
|
||||||
Serial.print("\r\n");
|
Serial.print("\r\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
CommandCodeEnum Command::getCodeEnum() {
|
CommandCodeEnum Command::getCodeEnum()
|
||||||
return commandCodeEnum;
|
{
|
||||||
|
return commandCodeEnum;
|
||||||
}
|
}
|
||||||
|
|
||||||
double Command::getX() {
|
double Command::getX()
|
||||||
return axisValue[0];
|
{
|
||||||
|
return axisValue[0];
|
||||||
}
|
}
|
||||||
|
|
||||||
double Command::getY() {
|
double Command::getY()
|
||||||
return axisValue[1];
|
{
|
||||||
|
return axisValue[1];
|
||||||
}
|
}
|
||||||
|
|
||||||
double Command::getZ() {
|
double Command::getZ()
|
||||||
return axisValue[2];
|
{
|
||||||
|
return axisValue[2];
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getA() {
|
long Command::getA()
|
||||||
return axisSpeedValue[0];
|
{
|
||||||
|
return axisSpeedValue[0];
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getB() {
|
long Command::getB()
|
||||||
return axisSpeedValue[1];
|
{
|
||||||
|
return axisSpeedValue[1];
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getC() {
|
long Command::getC()
|
||||||
return axisSpeedValue[2];
|
{
|
||||||
|
return axisSpeedValue[2];
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getP() {
|
long Command::getP()
|
||||||
return parameterId;
|
{
|
||||||
|
return parameterId;
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getV() {
|
long Command::getV()
|
||||||
return parameterValue;
|
{
|
||||||
|
return parameterValue;
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getW() {
|
long Command::getW()
|
||||||
return parameterValue2;
|
{
|
||||||
|
return parameterValue2;
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getT() {
|
long Command::getT()
|
||||||
return time;
|
{
|
||||||
|
return time;
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getE() {
|
long Command::getE()
|
||||||
return element;
|
{
|
||||||
|
return element;
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getM() {
|
long Command::getM()
|
||||||
return mode;
|
{
|
||||||
|
return mode;
|
||||||
}
|
}
|
||||||
|
|
||||||
long Command::getQ() {
|
long Command::getQ()
|
||||||
//msgQueue = 9876;
|
{
|
||||||
return msgQueue;
|
//msgQueue = 9876;
|
||||||
|
return msgQueue;
|
||||||
}
|
}
|
||||||
|
|
|
@ -7,9 +7,9 @@
|
||||||
enum CommandCodeEnum
|
enum CommandCodeEnum
|
||||||
{
|
{
|
||||||
CODE_UNDEFINED = -1,
|
CODE_UNDEFINED = -1,
|
||||||
G00 = 0,
|
G00 = 0,
|
||||||
G01 = 1,
|
G01 = 1,
|
||||||
G28 = 28,
|
G28 = 28,
|
||||||
F01 = 101,
|
F01 = 101,
|
||||||
F02 = 102,
|
F02 = 102,
|
||||||
F03 = 103,
|
F03 = 103,
|
||||||
|
@ -37,44 +37,46 @@ enum CommandCodeEnum
|
||||||
|
|
||||||
//#define NULL 0
|
//#define NULL 0
|
||||||
|
|
||||||
class Command {
|
class Command
|
||||||
CommandCodeEnum codeEnum;
|
{
|
||||||
|
CommandCodeEnum codeEnum;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
// Command(String);
|
// Command(String);
|
||||||
Command(char * commandChar);
|
Command(char *commandChar);
|
||||||
void print();
|
void print();
|
||||||
CommandCodeEnum getCodeEnum();
|
CommandCodeEnum getCodeEnum();
|
||||||
double getX();
|
double getX();
|
||||||
double getY();
|
double getY();
|
||||||
double getZ();
|
double getZ();
|
||||||
double getS();
|
double getS();
|
||||||
long getP();
|
long getP();
|
||||||
long getV();
|
long getV();
|
||||||
long getA();
|
long getA();
|
||||||
long getB();
|
long getB();
|
||||||
long getC();
|
long getC();
|
||||||
long getW();
|
long getW();
|
||||||
long getT();
|
long getT();
|
||||||
long getE();
|
long getE();
|
||||||
long getM();
|
long getM();
|
||||||
long getQ();
|
long getQ();
|
||||||
|
|
||||||
|
void printQAndNewLine();
|
||||||
|
|
||||||
void printQAndNewLine();
|
|
||||||
private:
|
private:
|
||||||
CommandCodeEnum getGCodeEnum(char* code);
|
CommandCodeEnum getGCodeEnum(char *code);
|
||||||
void getParameter(char* charPointer);
|
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;
|
|
||||||
|
|
||||||
|
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_ */
|
#endif /* COMMAND_H_ */
|
||||||
|
|
170
src/Config.h
170
src/Config.h
|
@ -22,130 +22,128 @@ const String COMM_REPORT_CMD_STATUS = "R05";
|
||||||
const String COMM_REPORT_CALIB_STATUS = "R06";
|
const String COMM_REPORT_CALIB_STATUS = "R06";
|
||||||
*/
|
*/
|
||||||
|
|
||||||
const char COMM_REPORT_CMD_IDLE[4] = {'R','0','0','\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_START[4] = {'R', '0', '1', '\0'};
|
||||||
const char COMM_REPORT_CMD_DONE[4] = {'R','0','2','\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_ERROR[4] = {'R', '0', '3', '\0'};
|
||||||
const char COMM_REPORT_CMD_BUSY[4] = {'R','0','4','\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_CMD_STATUS[4] = {'R', '0', '5', '\0'};
|
||||||
const char COMM_REPORT_CALIB_STATUS[4] = {'R','0','6','\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_NO_CONFIG[4] = {'R', '8', '8', '\0'};
|
||||||
const char COMM_REPORT_COMMENT[4] = {'R','9','9','\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_IDLE = 0;
|
||||||
const int COMM_REPORT_MOVE_STATUS_START_MOTOR = 1;
|
const int COMM_REPORT_MOVE_STATUS_START_MOTOR = 1;
|
||||||
const int COMM_REPORT_MOVE_STATUS_ACCELERATING = 2;
|
const int COMM_REPORT_MOVE_STATUS_ACCELERATING = 2;
|
||||||
const int COMM_REPORT_MOVE_STATUS_CRUISING = 3;
|
const int COMM_REPORT_MOVE_STATUS_CRUISING = 3;
|
||||||
const int COMM_REPORT_MOVE_STATUS_DECELERATING = 4;
|
const int COMM_REPORT_MOVE_STATUS_DECELERATING = 4;
|
||||||
const int COMM_REPORT_MOVE_STATUS_STOP_MOTOR = 5;
|
const int COMM_REPORT_MOVE_STATUS_STOP_MOTOR = 5;
|
||||||
const int COMM_REPORT_MOVE_STATUS_CRAWLING = 6;
|
const int COMM_REPORT_MOVE_STATUS_CRAWLING = 6;
|
||||||
const int COMM_REPORT_MOVE_STATUS_ERROR = -1;
|
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_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 int MOVEMENT_INTERRUPT_SPEED = 200; // Interrupt cycle in micro seconds
|
||||||
|
|
||||||
const unsigned int MOVEMENT_SPEED_BASE_TIME = 2000;
|
const unsigned int MOVEMENT_SPEED_BASE_TIME = 2000;
|
||||||
const unsigned int MOVEMENT_DELAY = 250;
|
const unsigned int MOVEMENT_DELAY = 250;
|
||||||
|
|
||||||
const long PARAM_VERSION_DEFAULT = 1;
|
const long PARAM_VERSION_DEFAULT = 1;
|
||||||
const long PARAM_TEST_DEFAULT = 0;
|
const long PARAM_TEST_DEFAULT = 0;
|
||||||
|
|
||||||
const long PARAM_CONFIG_OK_DEFAULT = 0;
|
const long PARAM_CONFIG_OK_DEFAULT = 0;
|
||||||
const long PARAM_USE_EEPROM_DEFAULT = 1;
|
const long PARAM_USE_EEPROM_DEFAULT = 1;
|
||||||
|
|
||||||
const long MOVEMENT_TIMEOUT_X_DEFAULT = 120;
|
const long MOVEMENT_TIMEOUT_X_DEFAULT = 120;
|
||||||
const long MOVEMENT_TIMEOUT_Y_DEFAULT = 120;
|
const long MOVEMENT_TIMEOUT_Y_DEFAULT = 120;
|
||||||
const long MOVEMENT_TIMEOUT_Z_DEFAULT = 120;
|
const long MOVEMENT_TIMEOUT_Z_DEFAULT = 120;
|
||||||
|
|
||||||
const long MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT = 0;
|
const long MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT = 0;
|
||||||
const long MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT = 0;
|
const long MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT = 0;
|
||||||
const long MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT = 0;
|
const long MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT = 0;
|
||||||
|
|
||||||
const long MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT = 0;
|
const long MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT = 0;
|
||||||
const long MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT = 0;
|
const long MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT = 0;
|
||||||
const long MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT = 0;
|
const long MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT = 0;
|
||||||
|
|
||||||
const long MOVEMENT_INVERT_MOTOR_X_DEFAULT = 0;
|
const long MOVEMENT_INVERT_MOTOR_X_DEFAULT = 0;
|
||||||
const long MOVEMENT_INVERT_MOTOR_Y_DEFAULT = 0;
|
const long MOVEMENT_INVERT_MOTOR_Y_DEFAULT = 0;
|
||||||
const long MOVEMENT_INVERT_MOTOR_Z_DEFAULT = 0;
|
const long MOVEMENT_INVERT_MOTOR_Z_DEFAULT = 0;
|
||||||
|
|
||||||
const long MOVEMENT_SECONDARY_MOTOR_X_DEFAULT = 1;
|
const long MOVEMENT_SECONDARY_MOTOR_X_DEFAULT = 1;
|
||||||
const long MOVEMENT_SECONDARY_MOTOR_INVERT_X_DEFAULT = 0;
|
const long MOVEMENT_SECONDARY_MOTOR_INVERT_X_DEFAULT = 0;
|
||||||
|
|
||||||
const long MOVEMENT_HOME_UP_X_DEFAULT = 0;
|
const long MOVEMENT_HOME_UP_X_DEFAULT = 0;
|
||||||
const long MOVEMENT_HOME_UP_Y_DEFAULT = 0;
|
const long MOVEMENT_HOME_UP_Y_DEFAULT = 0;
|
||||||
const long MOVEMENT_HOME_UP_Z_DEFAULT = 1;
|
const long MOVEMENT_HOME_UP_Z_DEFAULT = 1;
|
||||||
|
|
||||||
// numver of steps used for acceleration or deceleration
|
// numver of steps used for acceleration or deceleration
|
||||||
const long MOVEMENT_STEPS_ACC_DEC_X_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_Y_DEFAULT = 500;
|
||||||
const long MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT = 500;
|
const long MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT = 500;
|
||||||
|
|
||||||
// Minimum speed in steps per second
|
// Minimum speed in steps per second
|
||||||
const long MOVEMENT_MIN_SPD_X_DEFAULT = 50;
|
const long MOVEMENT_MIN_SPD_X_DEFAULT = 50;
|
||||||
const long MOVEMENT_MIN_SPD_Y_DEFAULT = 50;
|
const long MOVEMENT_MIN_SPD_Y_DEFAULT = 50;
|
||||||
const long MOVEMENT_MIN_SPD_Z_DEFAULT = 50;
|
const long MOVEMENT_MIN_SPD_Z_DEFAULT = 50;
|
||||||
|
|
||||||
// Maxumum speed in steps per second
|
// Maxumum speed in steps per second
|
||||||
const long MOVEMENT_MAX_SPD_X_DEFAULT = 800;
|
const long MOVEMENT_MAX_SPD_X_DEFAULT = 800;
|
||||||
const long MOVEMENT_MAX_SPD_Y_DEFAULT = 800;
|
const long MOVEMENT_MAX_SPD_Y_DEFAULT = 800;
|
||||||
const long MOVEMENT_MAX_SPD_Z_DEFAULT = 800;
|
const long MOVEMENT_MAX_SPD_Z_DEFAULT = 800;
|
||||||
|
|
||||||
// Use encoder (0 or 1)
|
// Use encoder (0 or 1)
|
||||||
const long ENCODER_ENABLED_X_DEFAULT = 0;
|
const long ENCODER_ENABLED_X_DEFAULT = 0;
|
||||||
const long ENCODER_ENABLED_Y_DEFAULT = 0;
|
const long ENCODER_ENABLED_Y_DEFAULT = 0;
|
||||||
const long ENCODER_ENABLED_Z_DEFAULT = 0;
|
const long ENCODER_ENABLED_Z_DEFAULT = 0;
|
||||||
|
|
||||||
// Type of enocder.
|
// Type of enocder.
|
||||||
// 0 = non-differential encoder, channel A,B
|
// 0 = non-differential encoder, channel A,B
|
||||||
// 1 = differenttial encoder, channel A, A*, B, B*
|
// 1 = differenttial encoder, channel A, A*, B, B*
|
||||||
const long ENCODER_TYPE_X_DEFAULT = 0;
|
const long ENCODER_TYPE_X_DEFAULT = 0;
|
||||||
const long ENCODER_TYPE_Y_DEFAULT = 0;
|
const long ENCODER_TYPE_Y_DEFAULT = 0;
|
||||||
const long ENCODER_TYPE_Z_DEFAULT = 0;
|
const long ENCODER_TYPE_Z_DEFAULT = 0;
|
||||||
|
|
||||||
// Position = encoder position * scaling / 100
|
// Position = encoder position * scaling / 100
|
||||||
const long ENCODER_SCALING_X_DEFAULT = 100;
|
const long ENCODER_SCALING_X_DEFAULT = 100;
|
||||||
const long ENCODER_SCALING_Y_DEFAULT = 100;
|
const long ENCODER_SCALING_Y_DEFAULT = 100;
|
||||||
const long ENCODER_SCALING_Z_DEFAULT = 100;
|
const long ENCODER_SCALING_Z_DEFAULT = 100;
|
||||||
|
|
||||||
// Number of stes missed before motor is seen as not moving
|
// 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_X_DEFAULT = 10;
|
||||||
const long ENCODER_MISSED_STEPS_MAX_Y_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_Z_DEFAULT = 10;
|
||||||
|
|
||||||
// How much a good step is substracted from the missed step total (1-99)
|
// 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_X_DEFAULT = 10;
|
||||||
const long ENCODER_MISSED_STEPS_DECAY_Y_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_Z_DEFAULT = 10;
|
||||||
|
|
||||||
// pin guard default settings
|
// pin guard default settings
|
||||||
const long PIN_GUARD_1_PIN_NR_DEFAULT = 0;
|
const long PIN_GUARD_1_PIN_NR_DEFAULT = 0;
|
||||||
const long PIN_GUARD_1_TIME_OUT_DEFAULT = 60;
|
const long PIN_GUARD_1_TIME_OUT_DEFAULT = 60;
|
||||||
const long PIN_GUARD_1_ACTIVE_STATE_DEFAULT = 1;
|
const long PIN_GUARD_1_ACTIVE_STATE_DEFAULT = 1;
|
||||||
|
|
||||||
const long PIN_GUARD_2_PIN_NR_DEFAULT = 0;
|
const long PIN_GUARD_2_PIN_NR_DEFAULT = 0;
|
||||||
const long PIN_GUARD_2_TIME_OUT_DEFAULT = 60;
|
const long PIN_GUARD_2_TIME_OUT_DEFAULT = 60;
|
||||||
const long PIN_GUARD_2_ACTIVE_STATE_DEFAULT = 1;
|
const long PIN_GUARD_2_ACTIVE_STATE_DEFAULT = 1;
|
||||||
|
|
||||||
const long PIN_GUARD_3_PIN_NR_DEFAULT = 0;
|
const long PIN_GUARD_3_PIN_NR_DEFAULT = 0;
|
||||||
const long PIN_GUARD_3_TIME_OUT_DEFAULT = 60;
|
const long PIN_GUARD_3_TIME_OUT_DEFAULT = 60;
|
||||||
const long PIN_GUARD_3_ACTIVE_STATE_DEFAULT = 1;
|
const long PIN_GUARD_3_ACTIVE_STATE_DEFAULT = 1;
|
||||||
|
|
||||||
const long PIN_GUARD_4_PIN_NR_DEFAULT = 0;
|
const long PIN_GUARD_4_PIN_NR_DEFAULT = 0;
|
||||||
const long PIN_GUARD_4_TIME_OUT_DEFAULT = 60;
|
const long PIN_GUARD_4_TIME_OUT_DEFAULT = 60;
|
||||||
const long PIN_GUARD_4_ACTIVE_STATE_DEFAULT = 1;
|
const long PIN_GUARD_4_ACTIVE_STATE_DEFAULT = 1;
|
||||||
|
|
||||||
const long PIN_GUARD_5_PIN_NR_DEFAULT = 0;
|
const long PIN_GUARD_5_PIN_NR_DEFAULT = 0;
|
||||||
const long PIN_GUARD_5_TIME_OUT_DEFAULT = 60;
|
const long PIN_GUARD_5_TIME_OUT_DEFAULT = 60;
|
||||||
const long PIN_GUARD_5_ACTIVE_STATE_DEFAULT = 1;
|
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";
|
const char SOFTWARE_VERSION[] = "GENESIS.V.01.08.EXPERIMENTAL\0";
|
||||||
|
|
||||||
|
|
|
@ -7,7 +7,7 @@
|
||||||
|
|
||||||
#include "CurrentState.h"
|
#include "CurrentState.h"
|
||||||
|
|
||||||
static CurrentState* instance;
|
static CurrentState *instance;
|
||||||
long x = 0;
|
long x = 0;
|
||||||
long y = 0;
|
long y = 0;
|
||||||
long z = 0;
|
long z = 0;
|
||||||
|
@ -15,120 +15,138 @@ unsigned int speed = 0;
|
||||||
bool endStopState[3][2];
|
bool endStopState[3][2];
|
||||||
long Q = 0;
|
long Q = 0;
|
||||||
|
|
||||||
CurrentState * CurrentState::getInstance() {
|
CurrentState *CurrentState::getInstance()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new CurrentState();
|
if (!instance)
|
||||||
};
|
{
|
||||||
return instance;
|
instance = new CurrentState();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
};
|
};
|
||||||
|
|
||||||
CurrentState::CurrentState() {
|
CurrentState::CurrentState()
|
||||||
x = 0;
|
{
|
||||||
y = 0;
|
x = 0;
|
||||||
z = 0;
|
y = 0;
|
||||||
speed = 0;
|
z = 0;
|
||||||
Q = 0;
|
speed = 0;
|
||||||
|
Q = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
long CurrentState::getX() {
|
long CurrentState::getX()
|
||||||
return x;
|
{
|
||||||
|
return x;
|
||||||
}
|
}
|
||||||
|
|
||||||
long CurrentState::getY() {
|
long CurrentState::getY()
|
||||||
return y;
|
{
|
||||||
|
return y;
|
||||||
}
|
}
|
||||||
|
|
||||||
long CurrentState::getZ() {
|
long CurrentState::getZ()
|
||||||
return z;
|
{
|
||||||
|
return z;
|
||||||
}
|
}
|
||||||
|
|
||||||
long* CurrentState::getPoint() {
|
long *CurrentState::getPoint()
|
||||||
static long currentPoint[3] = {x, y, z};
|
{
|
||||||
return currentPoint;
|
static long currentPoint[3] = {x, y, z};
|
||||||
|
return currentPoint;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::setX(long newX) {
|
void CurrentState::setX(long newX)
|
||||||
x = newX;
|
{
|
||||||
|
x = newX;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::setY(long newY) {
|
void CurrentState::setY(long newY)
|
||||||
y = newY;
|
{
|
||||||
|
y = newY;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::setZ(long newZ) {
|
void CurrentState::setZ(long newZ)
|
||||||
z = newZ;
|
{
|
||||||
|
z = newZ;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::setEndStopState(unsigned int axis, unsigned int position, bool state) {
|
void CurrentState::setEndStopState(unsigned int axis, unsigned int position, bool state)
|
||||||
endStopState[axis][position] = state;
|
{
|
||||||
|
endStopState[axis][position] = state;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::storeEndStops() {
|
void CurrentState::storeEndStops()
|
||||||
CurrentState::getInstance()->setEndStopState(0,0,digitalRead(X_MIN_PIN));
|
{
|
||||||
CurrentState::getInstance()->setEndStopState(0,1,digitalRead(X_MAX_PIN));
|
CurrentState::getInstance()->setEndStopState(0, 0, digitalRead(X_MIN_PIN));
|
||||||
CurrentState::getInstance()->setEndStopState(1,0,digitalRead(Y_MIN_PIN));
|
CurrentState::getInstance()->setEndStopState(0, 1, digitalRead(X_MAX_PIN));
|
||||||
CurrentState::getInstance()->setEndStopState(1,1,digitalRead(Y_MAX_PIN));
|
CurrentState::getInstance()->setEndStopState(1, 0, digitalRead(Y_MIN_PIN));
|
||||||
CurrentState::getInstance()->setEndStopState(2,0,digitalRead(Z_MIN_PIN));
|
CurrentState::getInstance()->setEndStopState(1, 1, digitalRead(Y_MAX_PIN));
|
||||||
CurrentState::getInstance()->setEndStopState(2,1,digitalRead(Z_MAX_PIN));
|
CurrentState::getInstance()->setEndStopState(2, 0, digitalRead(Z_MIN_PIN));
|
||||||
|
CurrentState::getInstance()->setEndStopState(2, 1, digitalRead(Z_MAX_PIN));
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::printPosition() {
|
void CurrentState::printPosition()
|
||||||
Serial.print("R82");
|
{
|
||||||
Serial.print(" X");
|
Serial.print("R82");
|
||||||
Serial.print(x);
|
Serial.print(" X");
|
||||||
Serial.print(" Y");
|
Serial.print(x);
|
||||||
Serial.print(y);
|
Serial.print(" Y");
|
||||||
Serial.print(" Z");
|
Serial.print(y);
|
||||||
Serial.print(z);
|
Serial.print(" Z");
|
||||||
// Serial.print("\r\n");
|
Serial.print(z);
|
||||||
printQAndNewLine();
|
// Serial.print("\r\n");
|
||||||
|
printQAndNewLine();
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::printBool(bool value)
|
void CurrentState::printBool(bool value)
|
||||||
{
|
{
|
||||||
if (value)
|
if (value)
|
||||||
{
|
{
|
||||||
Serial.print("1");
|
Serial.print("1");
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
Serial.print("0");
|
Serial.print("0");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::printEndStops() {
|
void CurrentState::printEndStops()
|
||||||
Serial.print("R81");
|
{
|
||||||
Serial.print(" XA");
|
Serial.print("R81");
|
||||||
printBool(endStopState[0][0]);
|
Serial.print(" XA");
|
||||||
Serial.print(" XB");
|
printBool(endStopState[0][0]);
|
||||||
printBool(endStopState[0][1]);
|
Serial.print(" XB");
|
||||||
Serial.print(" YA");
|
printBool(endStopState[0][1]);
|
||||||
printBool(endStopState[1][0]);
|
Serial.print(" YA");
|
||||||
Serial.print(" YB");
|
printBool(endStopState[1][0]);
|
||||||
printBool(endStopState[1][1]);
|
Serial.print(" YB");
|
||||||
Serial.print(" ZA");
|
printBool(endStopState[1][1]);
|
||||||
printBool(endStopState[2][0]);
|
Serial.print(" ZA");
|
||||||
Serial.print(" ZB");
|
printBool(endStopState[2][0]);
|
||||||
printBool(endStopState[2][1]);
|
Serial.print(" ZB");
|
||||||
//Serial.print("\r\n");
|
printBool(endStopState[2][1]);
|
||||||
printQAndNewLine();
|
//Serial.print("\r\n");
|
||||||
|
printQAndNewLine();
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::print() {
|
void CurrentState::print()
|
||||||
printPosition();
|
{
|
||||||
printEndStops();
|
printPosition();
|
||||||
|
printEndStops();
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::setQ(long q) {
|
void CurrentState::setQ(long q)
|
||||||
Q = q;
|
{
|
||||||
|
Q = q;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::resetQ() {
|
void CurrentState::resetQ()
|
||||||
Q = 0;
|
{
|
||||||
|
Q = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void CurrentState::printQAndNewLine() {
|
void CurrentState::printQAndNewLine()
|
||||||
Serial.print(" Q");
|
{
|
||||||
Serial.print(Q);
|
Serial.print(" Q");
|
||||||
Serial.print("\r\n");
|
Serial.print(Q);
|
||||||
|
Serial.print("\r\n");
|
||||||
}
|
}
|
||||||
|
|
|
@ -10,32 +10,32 @@
|
||||||
#include "Arduino.h"
|
#include "Arduino.h"
|
||||||
#include "pins.h"
|
#include "pins.h"
|
||||||
|
|
||||||
class CurrentState {
|
class CurrentState
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static CurrentState* getInstance();
|
static CurrentState *getInstance();
|
||||||
long getX();
|
long getX();
|
||||||
long getY();
|
long getY();
|
||||||
long getZ();
|
long getZ();
|
||||||
long* getPoint();
|
long *getPoint();
|
||||||
void setX(long);
|
void setX(long);
|
||||||
void setY(long);
|
void setY(long);
|
||||||
void setZ(long);
|
void setZ(long);
|
||||||
void setEndStopState(unsigned int, unsigned int, bool);
|
void setEndStopState(unsigned int, unsigned int, bool);
|
||||||
void printPosition();
|
void printPosition();
|
||||||
void storeEndStops();
|
void storeEndStops();
|
||||||
void printEndStops();
|
void printEndStops();
|
||||||
void print();
|
void print();
|
||||||
void printBool(bool);
|
void printBool(bool);
|
||||||
|
|
||||||
void setQ(long);
|
void setQ(long);
|
||||||
void resetQ();
|
void resetQ();
|
||||||
void printQAndNewLine();
|
void printQAndNewLine();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
CurrentState();
|
CurrentState();
|
||||||
CurrentState(CurrentState const&);
|
CurrentState(CurrentState const &);
|
||||||
void operator=(CurrentState const&);
|
void operator=(CurrentState const &);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* CURRENTSTATE_H_ */
|
#endif /* CURRENTSTATE_H_ */
|
||||||
|
|
|
@ -8,31 +8,34 @@
|
||||||
|
|
||||||
#include "F11Handler.h"
|
#include "F11Handler.h"
|
||||||
|
|
||||||
|
static F11Handler *instance;
|
||||||
|
|
||||||
static F11Handler* instance;
|
F11Handler *F11Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F11Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F11Handler * F11Handler::getInstance() {
|
F11Handler::F11Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F11Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F11Handler::F11Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F11Handler::execute(Command* command) {
|
int F11Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 HOME X\r\n");
|
{
|
||||||
}
|
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) {
|
if (LOGGING)
|
||||||
CurrentState::getInstance()->print();
|
{
|
||||||
}
|
CurrentState::getInstance()->print();
|
||||||
return 0;
|
}
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -14,17 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F11Handler : public GCodeHandler {
|
class F11Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F11Handler* getInstance();
|
static F11Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F11Handler();
|
F11Handler();
|
||||||
F11Handler(F11Handler const&);
|
F11Handler(F11Handler const &);
|
||||||
void operator=(F11Handler const&);
|
void operator=(F11Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F11HANDLER_H_ */
|
#endif /* F11HANDLER_H_ */
|
||||||
|
|
||||||
|
|
|
@ -8,31 +8,34 @@
|
||||||
|
|
||||||
#include "F12Handler.h"
|
#include "F12Handler.h"
|
||||||
|
|
||||||
|
static F12Handler *instance;
|
||||||
|
|
||||||
static F12Handler* instance;
|
F12Handler *F12Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F12Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F12Handler * F12Handler::getInstance() {
|
F12Handler::F12Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F12Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F12Handler::F12Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F12Handler::execute(Command* command) {
|
int F12Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 HOME Y\r\n");
|
{
|
||||||
}
|
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) {
|
if (LOGGING)
|
||||||
CurrentState::getInstance()->print();
|
{
|
||||||
}
|
CurrentState::getInstance()->print();
|
||||||
return 0;
|
}
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -14,17 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F12Handler : public GCodeHandler {
|
class F12Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F12Handler* getInstance();
|
static F12Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F12Handler();
|
F12Handler();
|
||||||
F12Handler(F12Handler const&);
|
F12Handler(F12Handler const &);
|
||||||
void operator=(F12Handler const&);
|
void operator=(F12Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F12HANDLER_H_ */
|
#endif /* F12HANDLER_H_ */
|
||||||
|
|
||||||
|
|
|
@ -8,31 +8,34 @@
|
||||||
|
|
||||||
#include "F13Handler.h"
|
#include "F13Handler.h"
|
||||||
|
|
||||||
|
static F13Handler *instance;
|
||||||
|
|
||||||
static F13Handler* instance;
|
F13Handler *F13Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F13Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F13Handler * F13Handler::getInstance() {
|
F13Handler::F13Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F13Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F13Handler::F13Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F13Handler::execute(Command* command) {
|
int F13Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 HOME Z\r\n");
|
{
|
||||||
}
|
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) {
|
if (LOGGING)
|
||||||
CurrentState::getInstance()->print();
|
{
|
||||||
}
|
CurrentState::getInstance()->print();
|
||||||
return 0;
|
}
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -14,17 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F13Handler : public GCodeHandler {
|
class F13Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F13Handler* getInstance();
|
static F13Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F13Handler();
|
F13Handler();
|
||||||
F13Handler(F13Handler const&);
|
F13Handler(F13Handler const &);
|
||||||
void operator=(F13Handler const&);
|
void operator=(F13Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F13HANDLER_H_ */
|
#endif /* F13HANDLER_H_ */
|
||||||
|
|
||||||
|
|
|
@ -8,41 +8,43 @@
|
||||||
|
|
||||||
#include "F14Handler.h"
|
#include "F14Handler.h"
|
||||||
|
|
||||||
|
static F14Handler *instance;
|
||||||
|
|
||||||
static F14Handler* instance;
|
F14Handler *F14Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F14Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F14Handler * F14Handler::getInstance() {
|
F14Handler::F14Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F14Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F14Handler::F14Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F14Handler::execute(Command* command) {
|
int F14Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
int ret = 0;
|
int ret = 0;
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 CALIBRATE X\r\n");
|
{
|
||||||
}
|
Serial.print("R99 CALIBRATE X\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
ret = StepperControl::getInstance()->calibrateAxis(0);
|
ret = StepperControl::getInstance()->calibrateAxis(0);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
if (ret == 0) {
|
if (ret == 0) {
|
||||||
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) {
|
if (LOGGING)
|
||||||
CurrentState::getInstance()->print();
|
{
|
||||||
}
|
CurrentState::getInstance()->print();
|
||||||
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -15,18 +15,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F14Handler : public GCodeHandler {
|
class F14Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F14Handler* getInstance();
|
static F14Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F14Handler();
|
F14Handler();
|
||||||
F14Handler(F14Handler const&);
|
F14Handler(F14Handler const &);
|
||||||
void operator=(F14Handler const&);
|
void operator=(F14Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F14HANDLER_H_ */
|
#endif /* F14HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -8,31 +8,35 @@
|
||||||
|
|
||||||
#include "F15Handler.h"
|
#include "F15Handler.h"
|
||||||
|
|
||||||
|
static F15Handler *instance;
|
||||||
|
|
||||||
static F15Handler* instance;
|
F15Handler *F15Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F15Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F15Handler * F15Handler::getInstance() {
|
F15Handler::F15Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F15Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F15Handler::F15Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F15Handler::execute(Command* command) {
|
int F15Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 HOME Z\r\n");
|
{
|
||||||
}
|
Serial.print("R99 HOME Z\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
StepperControl::getInstance()->calibrateAxis(1);
|
StepperControl::getInstance()->calibrateAxis(1);
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
CurrentState::getInstance()->print();
|
{
|
||||||
}
|
CurrentState::getInstance()->print();
|
||||||
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -15,18 +15,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F15Handler : public GCodeHandler {
|
class F15Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F15Handler* getInstance();
|
static F15Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F15Handler();
|
F15Handler();
|
||||||
F15Handler(F15Handler const&);
|
F15Handler(F15Handler const &);
|
||||||
void operator=(F15Handler const&);
|
void operator=(F15Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F15HANDLER_H_ */
|
#endif /* F15HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -8,33 +8,35 @@
|
||||||
|
|
||||||
#include "F16Handler.h"
|
#include "F16Handler.h"
|
||||||
|
|
||||||
|
static F16Handler *instance;
|
||||||
|
|
||||||
static F16Handler* instance;
|
F16Handler *F16Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F16Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F16Handler * F16Handler::getInstance() {
|
F16Handler::F16Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F16Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F16Handler::F16Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F16Handler::execute(Command* command) {
|
int F16Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 HOME Z\r\n");
|
{
|
||||||
}
|
Serial.print("R99 HOME Z\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
StepperControl::getInstance()->calibrateAxis(2);
|
StepperControl::getInstance()->calibrateAxis(2);
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
CurrentState::getInstance()->print();
|
{
|
||||||
}
|
CurrentState::getInstance()->print();
|
||||||
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -15,18 +15,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F16Handler : public GCodeHandler {
|
class F16Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F16Handler* getInstance();
|
static F16Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F16Handler();
|
F16Handler();
|
||||||
F16Handler(F16Handler const&);
|
F16Handler(F16Handler const &);
|
||||||
void operator=(F16Handler const&);
|
void operator=(F16Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F16HANDLER_H_ */
|
#endif /* F16HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -7,23 +7,25 @@
|
||||||
|
|
||||||
#include "F20Handler.h"
|
#include "F20Handler.h"
|
||||||
|
|
||||||
|
static F20Handler *instance;
|
||||||
|
|
||||||
static F20Handler* instance;
|
F20Handler *F20Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F20Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F20Handler * F20Handler::getInstance() {
|
F20Handler::F20Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F20Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F20Handler::F20Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F20Handler::execute(Command* command) {
|
int F20Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
ParameterList::getInstance()->readAllValues();
|
ParameterList::getInstance()->readAllValues();
|
||||||
|
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,16 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F20Handler : public GCodeHandler {
|
class F20Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F20Handler* getInstance();
|
static F20Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F20Handler();
|
F20Handler();
|
||||||
F20Handler(F20Handler const&);
|
F20Handler(F20Handler const &);
|
||||||
void operator=(F20Handler const&);
|
void operator=(F20Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F20HANDLER_H_ */
|
#endif /* F20HANDLER_H_ */
|
||||||
|
|
|
@ -7,23 +7,25 @@
|
||||||
|
|
||||||
#include "F21Handler.h"
|
#include "F21Handler.h"
|
||||||
|
|
||||||
|
static F21Handler *instance;
|
||||||
|
|
||||||
static F21Handler* instance;
|
F21Handler *F21Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F21Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F21Handler * F21Handler::getInstance() {
|
F21Handler::F21Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F21Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
|
@ -15,16 +15,18 @@
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
#include "ParameterList.h"
|
#include "ParameterList.h"
|
||||||
|
|
||||||
class F21Handler : public GCodeHandler {
|
class F21Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F21Handler* getInstance();
|
static F21Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F21Handler();
|
F21Handler();
|
||||||
F21Handler(F21Handler const&);
|
F21Handler(F21Handler const &);
|
||||||
void operator=(F21Handler const&);
|
void operator=(F21Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F21HANDLER_H_ */
|
#endif /* F21HANDLER_H_ */
|
||||||
|
|
|
@ -7,23 +7,25 @@
|
||||||
|
|
||||||
#include "F22Handler.h"
|
#include "F22Handler.h"
|
||||||
|
|
||||||
|
static F22Handler *instance;
|
||||||
|
|
||||||
static F22Handler* instance;
|
F22Handler *F22Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F22Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F22Handler * F22Handler::getInstance() {
|
F22Handler::F22Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F22Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F22Handler::F22Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F22Handler::execute(Command* command) {
|
int F22Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Serial.print("R99");
|
Serial.print("R99");
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
Serial.print("write value");
|
Serial.print("write value");
|
||||||
|
@ -42,7 +44,7 @@ Serial.print(" ");
|
||||||
Serial.print("\r\n");
|
Serial.print("\r\n");
|
||||||
*/
|
*/
|
||||||
|
|
||||||
ParameterList::getInstance()->writeValue(command->getP(), command->getV());
|
ParameterList::getInstance()->writeValue(command->getP(), command->getV());
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -15,16 +15,18 @@
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
#include "ParameterList.h"
|
#include "ParameterList.h"
|
||||||
|
|
||||||
class F22Handler : public GCodeHandler {
|
class F22Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F22Handler* getInstance();
|
static F22Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F22Handler();
|
F22Handler();
|
||||||
F22Handler(F22Handler const&);
|
F22Handler(F22Handler const &);
|
||||||
void operator=(F22Handler const&);
|
void operator=(F22Handler const &);
|
||||||
//long adjustStepAmount(long);
|
//long adjustStepAmount(long);
|
||||||
//long getNumberOfSteps(double, double);
|
//long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F22HANDLER_H_ */
|
#endif /* F22HANDLER_H_ */
|
||||||
|
|
|
@ -8,25 +8,25 @@
|
||||||
|
|
||||||
#include "F31Handler.h"
|
#include "F31Handler.h"
|
||||||
|
|
||||||
|
static F31Handler *instance;
|
||||||
|
|
||||||
static F31Handler* instance;
|
F31Handler *F31Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F31Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F31Handler * F31Handler::getInstance() {
|
F31Handler::F31Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F31Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -16,19 +16,18 @@
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
#include "StatusList.h"
|
#include "StatusList.h"
|
||||||
|
|
||||||
class F31Handler : public GCodeHandler {
|
class F31Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F31Handler* getInstance();
|
static F31Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F31Handler();
|
F31Handler();
|
||||||
F31Handler(F31Handler const&);
|
F31Handler(F31Handler const &);
|
||||||
void operator=(F31Handler const&);
|
void operator=(F31Handler const &);
|
||||||
//long adjustStepAmount(long);
|
//long adjustStepAmount(long);
|
||||||
//long getNumberOfSteps(double, double);
|
//long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F31HANDLER_H_ */
|
#endif /* F31HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -8,25 +8,25 @@
|
||||||
|
|
||||||
#include "F32Handler.h"
|
#include "F32Handler.h"
|
||||||
|
|
||||||
|
static F32Handler *instance;
|
||||||
|
|
||||||
static F32Handler* instance;
|
F32Handler *F32Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F32Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F32Handler * F32Handler::getInstance() {
|
F32Handler::F32Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F32Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -16,19 +16,18 @@
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
#include "StatusList.h"
|
#include "StatusList.h"
|
||||||
|
|
||||||
class F32Handler : public GCodeHandler {
|
class F32Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F32Handler* getInstance();
|
static F32Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F32Handler();
|
F32Handler();
|
||||||
F32Handler(F32Handler const&);
|
F32Handler(F32Handler const &);
|
||||||
void operator=(F32Handler const&);
|
void operator=(F32Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F32HANDLER_H_ */
|
#endif /* F32HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -9,23 +9,25 @@
|
||||||
|
|
||||||
#include "F41Handler.h"
|
#include "F41Handler.h"
|
||||||
|
|
||||||
|
static F41Handler *instance;
|
||||||
|
|
||||||
static F41Handler* instance;
|
F41Handler *F41Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F41Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F41Handler * F41Handler::getInstance() {
|
F41Handler::F41Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F41Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,20 +14,16 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "PinControl.h"
|
#include "PinControl.h"
|
||||||
|
|
||||||
class F41Handler : public GCodeHandler {
|
class F41Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F41Handler* getInstance();
|
static F41Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F41Handler();
|
F41Handler();
|
||||||
F41Handler(F41Handler const&);
|
F41Handler(F41Handler const &);
|
||||||
void operator=(F41Handler const&);
|
void operator=(F41Handler const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F41HANDLER_H_ */
|
#endif /* F41HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -7,23 +7,25 @@
|
||||||
|
|
||||||
#include "F42Handler.h"
|
#include "F42Handler.h"
|
||||||
|
|
||||||
|
static F42Handler *instance;
|
||||||
|
|
||||||
static F42Handler* instance;
|
F42Handler *F42Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F42Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F42Handler * F42Handler::getInstance() {
|
F42Handler::F42Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F42Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,20 +14,16 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "PinControl.h"
|
#include "PinControl.h"
|
||||||
|
|
||||||
class F42Handler : public GCodeHandler {
|
class F42Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F42Handler* getInstance();
|
static F42Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F42Handler();
|
F42Handler();
|
||||||
F42Handler(F42Handler const&);
|
F42Handler(F42Handler const &);
|
||||||
void operator=(F42Handler const&);
|
void operator=(F42Handler const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F42HANDLER_H_ */
|
#endif /* F42HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -9,30 +9,25 @@
|
||||||
|
|
||||||
#include "F43Handler.h"
|
#include "F43Handler.h"
|
||||||
|
|
||||||
|
static F43Handler *instance;
|
||||||
|
|
||||||
static F43Handler* instance;
|
F43Handler *F43Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F43Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F43Handler * F43Handler::getInstance() {
|
F43Handler::F43Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F43Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -14,14 +14,16 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "PinControl.h"
|
#include "PinControl.h"
|
||||||
|
|
||||||
class F43Handler : public GCodeHandler {
|
class F43Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F43Handler* getInstance();
|
static F43Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F43Handler();
|
F43Handler();
|
||||||
F43Handler(F43Handler const&);
|
F43Handler(F43Handler const &);
|
||||||
void operator=(F43Handler const&);
|
void operator=(F43Handler const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F43HANDLER_H_ */
|
#endif /* F43HANDLER_H_ */
|
||||||
|
|
|
@ -9,23 +9,25 @@
|
||||||
|
|
||||||
#include "F44Handler.h"
|
#include "F44Handler.h"
|
||||||
|
|
||||||
|
static F44Handler *instance;
|
||||||
|
|
||||||
static F44Handler* instance;
|
F44Handler *F44Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F44Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F44Handler * F44Handler::getInstance() {
|
F44Handler::F44Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F44Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,17 +14,16 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "PinControl.h"
|
#include "PinControl.h"
|
||||||
|
|
||||||
class F44Handler : public GCodeHandler {
|
class F44Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F44Handler* getInstance();
|
static F44Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F44Handler();
|
F44Handler();
|
||||||
F44Handler(F44Handler const&);
|
F44Handler(F44Handler const &);
|
||||||
void operator=(F44Handler const&);
|
void operator=(F44Handler const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F44HANDLER_H_ */
|
#endif /* F44HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -9,23 +9,25 @@
|
||||||
|
|
||||||
#include "F61Handler.h"
|
#include "F61Handler.h"
|
||||||
|
|
||||||
|
static F61Handler *instance;
|
||||||
|
|
||||||
static F61Handler* instance;
|
F61Handler *F61Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F61Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F61Handler * F61Handler::getInstance() {
|
F61Handler::F61Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F61Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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;
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,20 +14,16 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "ServoControl.h"
|
#include "ServoControl.h"
|
||||||
|
|
||||||
class F61Handler : public GCodeHandler {
|
class F61Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F61Handler* getInstance();
|
static F61Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F61Handler();
|
F61Handler();
|
||||||
F61Handler(F61Handler const&);
|
F61Handler(F61Handler const &);
|
||||||
void operator=(F61Handler const&);
|
void operator=(F61Handler const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F61HANDLER_H_ */
|
#endif /* F61HANDLER_H_ */
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -9,40 +9,40 @@
|
||||||
|
|
||||||
#include "F81Handler.h"
|
#include "F81Handler.h"
|
||||||
|
|
||||||
|
static F81Handler *instance;
|
||||||
|
|
||||||
static F81Handler* instance;
|
F81Handler *F81Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F81Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F81Handler * F81Handler::getInstance() {
|
F81Handler::F81Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F81Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F81Handler::F81Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F81Handler::execute(Command* command) {
|
int F81Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
Serial.print("home\r\n");
|
Serial.print("home\r\n");
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 Report end stops\r\n");
|
{
|
||||||
}
|
Serial.print("R99 Report end stops\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
// Report back the end stops
|
// Report back the end stops
|
||||||
CurrentState::getInstance()->storeEndStops();
|
CurrentState::getInstance()->storeEndStops();
|
||||||
CurrentState::getInstance()->printEndStops();
|
CurrentState::getInstance()->printEndStops();
|
||||||
|
|
||||||
// Also report back some selected pin numbers: 8, 9, 10, 13
|
// Also report back some selected pin numbers: 8, 9, 10, 13
|
||||||
PinControl::getInstance()->readValue( 8, 0);
|
PinControl::getInstance()->readValue(8, 0);
|
||||||
PinControl::getInstance()->readValue( 9, 0);
|
PinControl::getInstance()->readValue(9, 0);
|
||||||
PinControl::getInstance()->readValue(10, 0);
|
PinControl::getInstance()->readValue(10, 0);
|
||||||
PinControl::getInstance()->readValue(13, 0);
|
PinControl::getInstance()->readValue(13, 0);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -15,17 +15,18 @@
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
#include "PinControl.h"
|
#include "PinControl.h"
|
||||||
|
|
||||||
class F81Handler : public GCodeHandler {
|
class F81Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F81Handler* getInstance();
|
static F81Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F81Handler();
|
F81Handler();
|
||||||
F81Handler(F81Handler const&);
|
F81Handler(F81Handler const &);
|
||||||
void operator=(F81Handler const&);
|
void operator=(F81Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F81HANDLER_H_ */
|
#endif /* F81HANDLER_H_ */
|
||||||
|
|
||||||
|
|
|
@ -9,30 +9,30 @@
|
||||||
|
|
||||||
#include "F82Handler.h"
|
#include "F82Handler.h"
|
||||||
|
|
||||||
|
static F82Handler *instance;
|
||||||
|
|
||||||
static F82Handler* instance;
|
F82Handler *F82Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F82Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F82Handler * F82Handler::getInstance() {
|
F82Handler::F82Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F82Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F82Handler::F82Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F82Handler::execute(Command* command) {
|
int F82Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 Report current position\r\n");
|
{
|
||||||
}
|
Serial.print("R99 Report current position\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
CurrentState::getInstance()->printPosition();
|
CurrentState::getInstance()->printPosition();
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -14,17 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F82Handler : public GCodeHandler {
|
class F82Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F82Handler* getInstance();
|
static F82Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F82Handler();
|
F82Handler();
|
||||||
F82Handler(F82Handler const&);
|
F82Handler(F82Handler const &);
|
||||||
void operator=(F82Handler const&);
|
void operator=(F82Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F82HANDLER_H_ */
|
#endif /* F82HANDLER_H_ */
|
||||||
|
|
||||||
|
|
|
@ -9,33 +9,33 @@
|
||||||
|
|
||||||
#include "F83Handler.h"
|
#include "F83Handler.h"
|
||||||
|
|
||||||
|
static F83Handler *instance;
|
||||||
|
|
||||||
static F83Handler* instance;
|
F83Handler *F83Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F83Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
F83Handler * F83Handler::getInstance() {
|
F83Handler::F83Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new F83Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
F83Handler::F83Handler() {
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int F83Handler::execute(Command* command) {
|
int F83Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
Serial.print("R99 Report server version\r\n");
|
{
|
||||||
}
|
Serial.print("R99 Report server version\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
Serial.print("R83 ");
|
Serial.print("R83 ");
|
||||||
Serial.print(SOFTWARE_VERSION);
|
Serial.print(SOFTWARE_VERSION);
|
||||||
//Serial.print("\r\n");
|
//Serial.print("\r\n");
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -14,17 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class F83Handler : public GCodeHandler {
|
class F83Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static F83Handler* getInstance();
|
static F83Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
F83Handler();
|
F83Handler();
|
||||||
F83Handler(F83Handler const&);
|
F83Handler(F83Handler const &);
|
||||||
void operator=(F83Handler const&);
|
void operator=(F83Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* F83HANDLER_H_ */
|
#endif /* F83HANDLER_H_ */
|
||||||
|
|
||||||
|
|
|
@ -7,51 +7,49 @@
|
||||||
|
|
||||||
#include "G00Handler.h"
|
#include "G00Handler.h"
|
||||||
|
|
||||||
|
static G00Handler *instance;
|
||||||
|
|
||||||
static G00Handler* instance;
|
G00Handler *G00Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new G00Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
G00Handler * G00Handler::getInstance() {
|
G00Handler::G00Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new G00Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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");
|
if (LOGGING)
|
||||||
// Serial.print(" X ");
|
{
|
||||||
// Serial.print(command->getX());
|
CurrentState::getInstance()->print();
|
||||||
// Serial.print(" Y ");
|
}
|
||||||
// Serial.print(command->getY());
|
return 0;
|
||||||
// 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;
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,16 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class G00Handler : public GCodeHandler {
|
class G00Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static G00Handler* getInstance();
|
static G00Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
G00Handler();
|
G00Handler();
|
||||||
G00Handler(G00Handler const&);
|
G00Handler(G00Handler const &);
|
||||||
void operator=(G00Handler const&);
|
void operator=(G00Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* G00HANDLER_H_ */
|
#endif /* G00HANDLER_H_ */
|
||||||
|
|
|
@ -7,29 +7,32 @@
|
||||||
|
|
||||||
#include "G28Handler.h"
|
#include "G28Handler.h"
|
||||||
|
|
||||||
|
static G28Handler *instance;
|
||||||
|
|
||||||
static G28Handler* instance;
|
G28Handler *G28Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new G28Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
G28Handler * G28Handler::getInstance() {
|
G28Handler::G28Handler()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new G28Handler();
|
|
||||||
};
|
|
||||||
return instance;
|
|
||||||
}
|
|
||||||
;
|
|
||||||
|
|
||||||
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, false, false, true);
|
||||||
StepperControl::getInstance()->moveToCoords(0,0,0, 0,0,0, true, true, false);
|
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);
|
//StepperControl::getInstance()->moveAbsoluteConstant(0,0,0,HOME_MOVEMENT_SPEED_S_P_S,true);
|
||||||
if (LOGGING) {
|
if (LOGGING)
|
||||||
CurrentState::getInstance()->print();
|
{
|
||||||
}
|
CurrentState::getInstance()->print();
|
||||||
return 0;
|
}
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -14,16 +14,18 @@
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
|
|
||||||
class G28Handler : public GCodeHandler {
|
class G28Handler : public GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static G28Handler* getInstance();
|
static G28Handler *getInstance();
|
||||||
int execute(Command*);
|
int execute(Command *);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
G28Handler();
|
G28Handler();
|
||||||
G28Handler(G28Handler const&);
|
G28Handler(G28Handler const &);
|
||||||
void operator=(G28Handler const&);
|
void operator=(G28Handler const &);
|
||||||
long adjustStepAmount(long);
|
long adjustStepAmount(long);
|
||||||
long getNumberOfSteps(double, double);
|
long getNumberOfSteps(double, double);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* G28HANDLER_H_ */
|
#endif /* G28HANDLER_H_ */
|
||||||
|
|
|
@ -7,13 +7,15 @@
|
||||||
|
|
||||||
#include "GCodeHandler.h"
|
#include "GCodeHandler.h"
|
||||||
|
|
||||||
GCodeHandler::GCodeHandler() {
|
GCodeHandler::GCodeHandler()
|
||||||
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
GCodeHandler::~GCodeHandler() {
|
GCodeHandler::~GCodeHandler()
|
||||||
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
int GCodeHandler::execute(Command*) {
|
int GCodeHandler::execute(Command *)
|
||||||
return -1;
|
{
|
||||||
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
|
@ -9,11 +9,12 @@
|
||||||
#define GCODEHANDLER_H_
|
#define GCODEHANDLER_H_
|
||||||
#include "Command.h"
|
#include "Command.h"
|
||||||
|
|
||||||
class GCodeHandler {
|
class GCodeHandler
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
GCodeHandler();
|
GCodeHandler();
|
||||||
virtual ~GCodeHandler();
|
virtual ~GCodeHandler();
|
||||||
virtual int execute(Command*);
|
virtual int execute(Command *);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* GCODEHANDLER_H_ */
|
#endif /* GCODEHANDLER_H_ */
|
||||||
|
|
|
@ -9,31 +9,33 @@
|
||||||
#include "GCodeProcessor.h"
|
#include "GCodeProcessor.h"
|
||||||
#include "CurrentState.h"
|
#include "CurrentState.h"
|
||||||
|
|
||||||
GCodeProcessor::GCodeProcessor() {
|
GCodeProcessor::GCodeProcessor()
|
||||||
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
GCodeProcessor::~GCodeProcessor() {
|
GCodeProcessor::~GCodeProcessor()
|
||||||
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
void GCodeProcessor::printCommandLog(Command* command) {
|
void GCodeProcessor::printCommandLog(Command *command)
|
||||||
Serial.print("command == NULL: ");
|
{
|
||||||
Serial.println("\r\n");
|
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();
|
long Q = command->getQ();
|
||||||
CurrentState::getInstance()->setQ(Q);
|
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
|
// Tim 2017-04-15 Disable until the raspberry code is ready
|
||||||
// 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
|
|
||||||
/*
|
|
||||||
if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
|
if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
|
||||||
if ( command->getCodeEnum() == G00 ||
|
if ( command->getCodeEnum() == G00 ||
|
||||||
command->getCodeEnum() == G01 ||
|
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 (command == NULL)
|
||||||
if(LOGGING) {
|
{
|
||||||
printCommandLog(command);
|
if (LOGGING)
|
||||||
}
|
{
|
||||||
return -1;
|
printCommandLog(command);
|
||||||
}
|
}
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
if(command->getCodeEnum() == CODE_UNDEFINED) {
|
if (command->getCodeEnum() == CODE_UNDEFINED)
|
||||||
if(LOGGING) {
|
{
|
||||||
printCommandLog(command);
|
if (LOGGING)
|
||||||
}
|
{
|
||||||
return -1;
|
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) {
|
if (handler == NULL)
|
||||||
Serial.println("R99 handler == NULL\r\n");
|
{
|
||||||
return -1;
|
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);
|
Serial.print(COMM_REPORT_CMD_START);
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
|
||||||
execution = handler->execute(command);
|
execution = handler->execute(command);
|
||||||
if(execution == 0) {
|
if (execution == 0)
|
||||||
Serial.print(COMM_REPORT_CMD_DONE);
|
{
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
Serial.print(COMM_REPORT_CMD_DONE);
|
||||||
} else {
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
Serial.print(COMM_REPORT_CMD_ERROR);
|
}
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
else
|
||||||
}
|
{
|
||||||
|
Serial.print(COMM_REPORT_CMD_ERROR);
|
||||||
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
}
|
||||||
|
|
||||||
CurrentState::getInstance()->resetQ();
|
CurrentState::getInstance()->resetQ();
|
||||||
return execution;
|
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
|
// These are if statements so they can be disabled as test
|
||||||
// Usefull when running into memory issues again
|
// 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 == F14)
|
||||||
if (codeEnum == F12) {handler = F12Handler::getInstance();}
|
{
|
||||||
if (codeEnum == F13) {handler = F13Handler::getInstance();}
|
handler = F14Handler::getInstance();
|
||||||
|
}
|
||||||
|
if (codeEnum == F15)
|
||||||
|
{
|
||||||
|
handler = F15Handler::getInstance();
|
||||||
|
}
|
||||||
|
if (codeEnum == F16)
|
||||||
|
{
|
||||||
|
handler = F16Handler::getInstance();
|
||||||
|
}
|
||||||
|
|
||||||
if (codeEnum == F14) {handler = F14Handler::getInstance();}
|
if (codeEnum == F20)
|
||||||
if (codeEnum == F15) {handler = F15Handler::getInstance();}
|
{
|
||||||
if (codeEnum == F16) {handler = F16Handler::getInstance();}
|
handler = F20Handler::getInstance();
|
||||||
|
}
|
||||||
|
if (codeEnum == F21)
|
||||||
|
{
|
||||||
|
handler = F21Handler::getInstance();
|
||||||
|
}
|
||||||
|
if (codeEnum == F22)
|
||||||
|
{
|
||||||
|
handler = F22Handler::getInstance();
|
||||||
|
}
|
||||||
|
|
||||||
if (codeEnum == F20) {handler = F20Handler::getInstance();}
|
// if (codeEnum == F31) {handler = F31Handler::getInstance();}
|
||||||
if (codeEnum == F21) {handler = F21Handler::getInstance();}
|
// if (codeEnum == F32) {handler = F32Handler::getInstance();}
|
||||||
if (codeEnum == F22) {handler = F22Handler::getInstance();}
|
|
||||||
|
|
||||||
// if (codeEnum == F31) {handler = F31Handler::getInstance();}
|
if (codeEnum == F41)
|
||||||
// if (codeEnum == F32) {handler = F32Handler::getInstance();}
|
{
|
||||||
|
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 == F61)
|
||||||
if (codeEnum == F42) {handler = F42Handler::getInstance();}
|
{
|
||||||
if (codeEnum == F43) {handler = F43Handler::getInstance();}
|
handler = F61Handler::getInstance();
|
||||||
if (codeEnum == F44) {handler = F44Handler::getInstance();}
|
}
|
||||||
|
|
||||||
if (codeEnum == F61) {handler = F61Handler::getInstance();}
|
if (codeEnum == F81)
|
||||||
|
{
|
||||||
|
handler = F81Handler::getInstance();
|
||||||
|
}
|
||||||
|
if (codeEnum == F82)
|
||||||
|
{
|
||||||
|
handler = F82Handler::getInstance();
|
||||||
|
}
|
||||||
|
if (codeEnum == F83)
|
||||||
|
{
|
||||||
|
handler = F83Handler::getInstance();
|
||||||
|
}
|
||||||
|
if (codeEnum == F84)
|
||||||
|
{
|
||||||
|
handler = F84Handler::getInstance();
|
||||||
|
}
|
||||||
|
|
||||||
if (codeEnum == F81) {handler = F81Handler::getInstance();}
|
return handler;
|
||||||
if (codeEnum == F82) {handler = F82Handler::getInstance();}
|
|
||||||
if (codeEnum == F83) {handler = F83Handler::getInstance();}
|
|
||||||
if (codeEnum == F84) {handler = F84Handler::getInstance();}
|
|
||||||
|
|
||||||
|
|
||||||
return handler;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -42,15 +42,18 @@
|
||||||
#include "F83Handler.h"
|
#include "F83Handler.h"
|
||||||
#include "F84Handler.h"
|
#include "F84Handler.h"
|
||||||
|
|
||||||
class GCodeProcessor {
|
class GCodeProcessor
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
GCodeProcessor();
|
GCodeProcessor();
|
||||||
virtual ~GCodeProcessor();
|
virtual ~GCodeProcessor();
|
||||||
int execute(Command* command);
|
int execute(Command *command);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
GCodeHandler* getGCodeHandler(CommandCodeEnum);
|
GCodeHandler *getGCodeHandler(CommandCodeEnum);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
void printCommandLog(Command*);
|
void printCommandLog(Command *);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* GCODEPROCESSOR_H_ */
|
#endif /* GCODEPROCESSOR_H_ */
|
||||||
|
|
|
@ -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
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
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
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
||||||
SOFTWARE.
|
SOFTWARE.
|
||||||
|
|
|
@ -25,12 +25,12 @@ extern struct __freelist *__flp;
|
||||||
/* Calculates the size of the free list */
|
/* Calculates the size of the free list */
|
||||||
int freeListSize()
|
int freeListSize()
|
||||||
{
|
{
|
||||||
struct __freelist* current;
|
struct __freelist *current;
|
||||||
int total = 0;
|
int total = 0;
|
||||||
for (current = __flp; current; current = current->nx)
|
for (current = __flp; current; current = current->nx)
|
||||||
{
|
{
|
||||||
total += 2; /* Add two bytes for the memory block's header */
|
total += 2; /* Add two bytes for the memory block's header */
|
||||||
total += (int) current->sz;
|
total += (int)current->sz;
|
||||||
}
|
}
|
||||||
|
|
||||||
return total;
|
return total;
|
||||||
|
|
|
@ -2,7 +2,7 @@
|
||||||
// http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1213583720/15
|
// http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1213583720/15
|
||||||
// Extended by Matthew Murdoch to include walking of the free list.
|
// Extended by Matthew Murdoch to include walking of the free list.
|
||||||
|
|
||||||
#ifndef MEMORY_FREE_H
|
#ifndef MEMORY_FREE_H
|
||||||
#define MEMORY_FREE_H
|
#define MEMORY_FREE_H
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
|
@ -11,7 +11,7 @@ extern "C" {
|
||||||
|
|
||||||
int freeMemory();
|
int freeMemory();
|
||||||
|
|
||||||
#ifdef __cplusplus
|
#ifdef __cplusplus
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -1,82 +1,97 @@
|
||||||
#include "ParameterList.h"
|
#include "ParameterList.h"
|
||||||
#include <EEPROM.h>
|
#include <EEPROM.h>
|
||||||
|
|
||||||
static ParameterList* instanceParam;
|
static ParameterList *instanceParam;
|
||||||
int paramValues[PARAM_NR_OF_PARAMS];
|
int paramValues[PARAM_NR_OF_PARAMS];
|
||||||
|
|
||||||
ParameterList * ParameterList::getInstance() {
|
ParameterList *ParameterList::getInstance()
|
||||||
if (!instanceParam) {
|
{
|
||||||
instanceParam = new ParameterList();
|
if (!instanceParam)
|
||||||
};
|
{
|
||||||
return instanceParam;
|
instanceParam = new ParameterList();
|
||||||
|
};
|
||||||
|
return instanceParam;
|
||||||
}
|
}
|
||||||
|
|
||||||
ParameterList::ParameterList() {
|
ParameterList::ParameterList()
|
||||||
// at the first boot, load default parameters and set the parameter version
|
{
|
||||||
// so during subsequent boots the values are just loaded from eeprom
|
// at the first boot, load default parameters and set the parameter version
|
||||||
// unless the eeprom is disabled with a parameter
|
// 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);
|
int paramVersion = readValueEeprom(0);
|
||||||
if (paramVersion <= 0) {
|
if (paramVersion <= 0)
|
||||||
setAllValuesToDefault();
|
{
|
||||||
writeAllValuesToEeprom();
|
setAllValuesToDefault();
|
||||||
} else {
|
writeAllValuesToEeprom();
|
||||||
//if (readValueEeprom(PARAM_USE_EEPROM) == 1) {
|
}
|
||||||
readAllValuesFromEeprom();
|
else
|
||||||
//} else {
|
{
|
||||||
// setAllValuesToDefault();
|
//if (readValueEeprom(PARAM_USE_EEPROM) == 1) {
|
||||||
//}
|
readAllValuesFromEeprom();
|
||||||
}
|
//} else {
|
||||||
|
// setAllValuesToDefault();
|
||||||
|
//}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// ===== Interface functions for the raspberry pi =====
|
// ===== Interface functions for the raspberry pi =====
|
||||||
|
|
||||||
int ParameterList::readValue(int id) {
|
int ParameterList::readValue(int id)
|
||||||
|
{
|
||||||
|
|
||||||
// Check if the value is an existing parameter
|
// Check if the value is an existing parameter
|
||||||
if (validParam(id)) {
|
if (validParam(id))
|
||||||
// Retrieve the value from memory
|
{
|
||||||
int value = paramValues[id];
|
// Retrieve the value from memory
|
||||||
|
int value = paramValues[id];
|
||||||
|
|
||||||
// Send to the raspberrt pi
|
// Send to the raspberrt pi
|
||||||
Serial.print("R21");
|
Serial.print("R21");
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
Serial.print("P");
|
Serial.print("P");
|
||||||
Serial.print(id);
|
Serial.print(id);
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
Serial.print("V");
|
Serial.print("V");
|
||||||
Serial.print(value);
|
Serial.print(value);
|
||||||
//Serial.print("\r\n");
|
//Serial.print("\r\n");
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
Serial.print("R99 Error: invalid parameter id\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
} else {
|
return 0;
|
||||||
Serial.print("R99 Error: invalid parameter id\r\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
return 0;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
int ParameterList::writeValue(int id, int value) {
|
int ParameterList::writeValue(int id, int value)
|
||||||
|
{
|
||||||
|
|
||||||
if (paramChangeNr < 9999) {
|
if (paramChangeNr < 9999)
|
||||||
paramChangeNr++;
|
{
|
||||||
} else {
|
paramChangeNr++;
|
||||||
paramChangeNr = 0;
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
paramChangeNr = 0;
|
||||||
|
}
|
||||||
|
|
||||||
// Check if the value is a valid parameter
|
// Check if the value is a valid parameter
|
||||||
if (validParam(id)) {
|
if (validParam(id))
|
||||||
// Store the value in memory
|
{
|
||||||
paramValues[id] = value;
|
// Store the value in memory
|
||||||
writeValueEeprom(id, value);
|
paramValues[id] = value;
|
||||||
} else {
|
writeValueEeprom(id, value);
|
||||||
Serial.print("R99 Error: invalid parameter id\r\n");
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
Serial.print("R99 Error: invalid parameter id\r\n");
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
/*
|
|
||||||
// Debugging output
|
// Debugging output
|
||||||
Serial.print("R99");
|
Serial.print("R99");
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
|
@ -93,264 +108,400 @@ int ParameterList::writeValue(int id, int value) {
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// If any value is written,
|
// If any value is written,
|
||||||
// trigger the loading of the new configuration in all other modules
|
// trigger the loading of the new configuration in all other modules
|
||||||
sendConfigToModules();
|
sendConfigToModules();
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void ParameterList::sendConfigToModules()
|
||||||
void ParameterList::sendConfigToModules() {
|
{
|
||||||
// Trigger other modules to load the new values
|
// Trigger other modules to load the new values
|
||||||
PinGuard::getInstance()->loadConfig();
|
PinGuard::getInstance()->loadConfig();
|
||||||
}
|
}
|
||||||
|
|
||||||
int ParameterList::readAllValues() {
|
int ParameterList::readAllValues()
|
||||||
|
{
|
||||||
|
|
||||||
|
// Make a dump of all values
|
||||||
// Make a dump of all values
|
// Check if it's a valid value to keep the junk out of the list
|
||||||
// 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++)
|
||||||
for (int i=0; i < PARAM_NR_OF_PARAMS; i++) {
|
{
|
||||||
if (validParam(i)) {
|
if (validParam(i))
|
||||||
readValue(i);
|
{
|
||||||
}
|
readValue(i);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int ParameterList::getValue(int id) {
|
int ParameterList::getValue(int id)
|
||||||
return paramValues[id];
|
{
|
||||||
|
return paramValues[id];
|
||||||
}
|
}
|
||||||
|
|
||||||
int ParameterList::paramChangeNumber() {
|
int ParameterList::paramChangeNumber()
|
||||||
return paramChangeNr;
|
{
|
||||||
|
return paramChangeNr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// ===== eeprom handling ====
|
// ===== eeprom handling ====
|
||||||
|
|
||||||
int ParameterList::readValueEeprom(int id) {
|
int ParameterList::readValueEeprom(int id)
|
||||||
|
{
|
||||||
|
|
||||||
// Assume all values are ints and calculate address for that
|
// Assume all values are ints and calculate address for that
|
||||||
int address = id * 2;
|
int address = id * 2;
|
||||||
|
|
||||||
//Read the 2 bytes from the eeprom memory.
|
//Read the 2 bytes from the eeprom memory.
|
||||||
long two = EEPROM.read(address);
|
long two = EEPROM.read(address);
|
||||||
long one = EEPROM.read(address + 1);
|
long one = EEPROM.read(address + 1);
|
||||||
|
|
||||||
//Return the recomposed long by using bitshift.
|
//Return the recomposed long by using bitshift.
|
||||||
return ((two << 0) & 0xFF) + ((one << 8) & 0xFFFF);
|
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
|
// Assume all values are ints and calculate address for that
|
||||||
int address = id * 2;
|
int address = id * 2;
|
||||||
|
|
||||||
//Decomposition from a int to 2 bytes by using bitshift.
|
//Decomposition from a int to 2 bytes by using bitshift.
|
||||||
//One = Most significant -> Two = Least significant byte
|
//One = Most significant -> Two = Least significant byte
|
||||||
byte two = (value & 0xFF);
|
byte two = (value & 0xFF);
|
||||||
byte one = ((value >> 8) & 0xFF);
|
byte one = ((value >> 8) & 0xFF);
|
||||||
|
|
||||||
//Write the 4 bytes into the eeprom memory.
|
//Write the 4 bytes into the eeprom memory.
|
||||||
EEPROM.write(address , two);
|
EEPROM.write(address, two);
|
||||||
EEPROM.write(address + 1, one);
|
EEPROM.write(address + 1, one);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
int ParameterList::readAllValuesFromEeprom() {
|
int ParameterList::readAllValuesFromEeprom()
|
||||||
// Write all existing values to eeprom
|
{
|
||||||
for (int i=0; i < PARAM_NR_OF_PARAMS; i++) {
|
// Write all existing values to eeprom
|
||||||
if (validParam(i)) {
|
for (int i = 0; i < PARAM_NR_OF_PARAMS; i++)
|
||||||
paramValues[i] = readValueEeprom(i);
|
{
|
||||||
if (paramValues[i] == -1) {
|
if (validParam(i))
|
||||||
// When parameters are still on default,
|
{
|
||||||
// load a good value and save it
|
paramValues[i] = readValueEeprom(i);
|
||||||
loadDefaultValue(i);
|
if (paramValues[i] == -1)
|
||||||
writeValueEeprom(i,paramValues[i]);
|
{
|
||||||
}
|
// When parameters are still on default,
|
||||||
}
|
// load a good value and save it
|
||||||
}
|
loadDefaultValue(i);
|
||||||
|
writeValueEeprom(i, paramValues[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int ParameterList::writeAllValuesToEeprom() {
|
int ParameterList::writeAllValuesToEeprom()
|
||||||
// Write all existing values to eeprom
|
{
|
||||||
for (int i=0; i < 150; i++)
|
// Write all existing values to eeprom
|
||||||
{
|
for (int i = 0; i < 150; i++)
|
||||||
if (validParam(i)) {
|
{
|
||||||
writeValueEeprom(i,paramValues[i]);
|
if (validParam(i))
|
||||||
}
|
{
|
||||||
}
|
writeValueEeprom(i, paramValues[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// ==== parameter valdation and defaults
|
// ==== parameter valdation and defaults
|
||||||
|
|
||||||
int ParameterList::setAllValuesToDefault() {
|
int ParameterList::setAllValuesToDefault()
|
||||||
// Copy default values to the memory values
|
{
|
||||||
for (int i=0; i < PARAM_NR_OF_PARAMS; i++)
|
// Copy default values to the memory values
|
||||||
{
|
for (int i = 0; i < PARAM_NR_OF_PARAMS; i++)
|
||||||
if (validParam(i)) {
|
{
|
||||||
loadDefaultValue(i);
|
if (validParam(i))
|
||||||
}
|
{
|
||||||
}
|
loadDefaultValue(i);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ParameterList::loadDefaultValue(int id) {
|
void ParameterList::loadDefaultValue(int id)
|
||||||
|
{
|
||||||
|
|
||||||
switch(id)
|
switch (id)
|
||||||
{
|
{
|
||||||
case PARAM_VERSION : paramValues[id] = PARAM_VERSION_DEFAULT; break;
|
case PARAM_VERSION:
|
||||||
case PARAM_TEST : paramValues[id] = PARAM_TEST_DEFAULT; break;
|
paramValues[id] = PARAM_VERSION_DEFAULT;
|
||||||
case PARAM_CONFIG_OK : paramValues[id] = PARAM_CONFIG_OK_DEFAULT; break;
|
break;
|
||||||
case PARAM_USE_EEPROM : paramValues[id] = PARAM_USE_EEPROM; 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_X:
|
||||||
case MOVEMENT_TIMEOUT_Y : paramValues[id] = MOVEMENT_TIMEOUT_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_TIMEOUT_X_DEFAULT;
|
||||||
case MOVEMENT_TIMEOUT_Z : paramValues[id] = MOVEMENT_TIMEOUT_Z_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_INVERT_ENDPOINTS_Y : paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_X_DEFAULT;
|
||||||
case MOVEMENT_INVERT_ENDPOINTS_Z : paramValues[id] = MOVEMENT_INVERT_ENDPOINTS_Z_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_ENABLE_ENDPOINTS_Y : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_X_DEFAULT;
|
||||||
case MOVEMENT_ENABLE_ENDPOINTS_Z : paramValues[id] = MOVEMENT_ENABLE_ENDPOINTS_Z_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_INVERT_MOTOR_Y : paramValues[id] = MOVEMENT_INVERT_MOTOR_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_INVERT_MOTOR_X_DEFAULT;
|
||||||
case MOVEMENT_INVERT_MOTOR_Z : paramValues[id] = MOVEMENT_INVERT_MOTOR_Z_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_SECONDARY_MOTOR_INVERT_X : paramValues[id] = MOVEMENT_SECONDARY_MOTOR_INVERT_X_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_STEPS_ACC_DEC_Y : paramValues[id] = MOVEMENT_STEPS_ACC_DEC_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_STEPS_ACC_DEC_X_DEFAULT;
|
||||||
case MOVEMENT_STEPS_ACC_DEC_Z : paramValues[id] = MOVEMENT_STEPS_ACC_DEC_Z_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_HOME_UP_Y : paramValues[id] = MOVEMENT_HOME_UP_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_HOME_UP_X_DEFAULT;
|
||||||
case MOVEMENT_HOME_UP_Z : paramValues[id] = MOVEMENT_HOME_UP_Z_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_MIN_SPD_Y : paramValues[id] = MOVEMENT_MIN_SPD_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_MIN_SPD_X_DEFAULT;
|
||||||
case MOVEMENT_MIN_SPD_Z : paramValues[id] = MOVEMENT_MIN_SPD_Z_DEFAULT; break;
|
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_X:
|
||||||
case MOVEMENT_MAX_SPD_Y : paramValues[id] = MOVEMENT_MAX_SPD_Y_DEFAULT; break;
|
paramValues[id] = MOVEMENT_MAX_SPD_X_DEFAULT;
|
||||||
case MOVEMENT_MAX_SPD_Z : paramValues[id] = MOVEMENT_MAX_SPD_Z_DEFAULT; break;
|
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_X:
|
||||||
case ENCODER_ENABLED_Y : paramValues[id] = ENCODER_ENABLED_Y_DEFAULT; break;
|
paramValues[id] = ENCODER_ENABLED_X_DEFAULT;
|
||||||
case ENCODER_ENABLED_Z : paramValues[id] = ENCODER_ENABLED_Z_DEFAULT; break;
|
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_X:
|
||||||
case ENCODER_TYPE_Y : paramValues[id] = ENCODER_TYPE_Y_DEFAULT; break;
|
paramValues[id] = ENCODER_TYPE_X_DEFAULT;
|
||||||
case ENCODER_TYPE_Z : paramValues[id] = ENCODER_TYPE_Z_DEFAULT; break;
|
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_X:
|
||||||
case ENCODER_MISSED_STEPS_MAX_Y : paramValues[id] = ENCODER_MISSED_STEPS_MAX_Y_DEFAULT; break;
|
paramValues[id] = ENCODER_MISSED_STEPS_MAX_X_DEFAULT;
|
||||||
case ENCODER_MISSED_STEPS_MAX_Z : paramValues[id] = ENCODER_MISSED_STEPS_MAX_Z_DEFAULT; break;
|
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_X:
|
||||||
case ENCODER_SCALING_Y : paramValues[id] = ENCODER_SCALING_Y_DEFAULT; break;
|
paramValues[id] = ENCODER_SCALING_X_DEFAULT;
|
||||||
case ENCODER_SCALING_Z : paramValues[id] = ENCODER_SCALING_Z_DEFAULT; break;
|
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_X:
|
||||||
case ENCODER_MISSED_STEPS_DECAY_Y : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Y_DEFAULT; break;
|
paramValues[id] = ENCODER_MISSED_STEPS_DECAY_X_DEFAULT;
|
||||||
case ENCODER_MISSED_STEPS_DECAY_Z : paramValues[id] = ENCODER_MISSED_STEPS_DECAY_Z_DEFAULT; break;
|
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_PIN_NR:
|
||||||
case PIN_GUARD_1_TIME_OUT : paramValues[id] = PIN_GUARD_1_TIME_OUT_DEFAULT; break;
|
paramValues[id] = PIN_GUARD_1_PIN_NR_DEFAULT;
|
||||||
case PIN_GUARD_1_ACTIVE_STATE : paramValues[id] = PIN_GUARD_1_ACTIVE_STATE_DEFAULT; break;
|
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_PIN_NR:
|
||||||
case PIN_GUARD_2_TIME_OUT : paramValues[id] = PIN_GUARD_2_TIME_OUT_DEFAULT; break;
|
paramValues[id] = PIN_GUARD_2_PIN_NR_DEFAULT;
|
||||||
case PIN_GUARD_2_ACTIVE_STATE : paramValues[id] = PIN_GUARD_2_ACTIVE_STATE_DEFAULT; break;
|
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_PIN_NR:
|
||||||
case PIN_GUARD_3_TIME_OUT : paramValues[id] = PIN_GUARD_3_TIME_OUT_DEFAULT; break;
|
paramValues[id] = PIN_GUARD_3_PIN_NR_DEFAULT;
|
||||||
case PIN_GUARD_3_ACTIVE_STATE : paramValues[id] = PIN_GUARD_3_ACTIVE_STATE_DEFAULT; break;
|
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_PIN_NR:
|
||||||
case PIN_GUARD_4_TIME_OUT : paramValues[id] = PIN_GUARD_4_TIME_OUT_DEFAULT; break;
|
paramValues[id] = PIN_GUARD_4_PIN_NR_DEFAULT;
|
||||||
case PIN_GUARD_4_ACTIVE_STATE : paramValues[id] = PIN_GUARD_4_ACTIVE_STATE_DEFAULT; break;
|
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_PIN_NR:
|
||||||
case PIN_GUARD_5_TIME_OUT : paramValues[id] = PIN_GUARD_5_TIME_OUT_DEFAULT; break;
|
paramValues[id] = PIN_GUARD_5_PIN_NR_DEFAULT;
|
||||||
case PIN_GUARD_5_ACTIVE_STATE : paramValues[id] = PIN_GUARD_5_ACTIVE_STATE_DEFAULT; break;
|
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
|
// Check if the id is a valid one
|
||||||
switch(id)
|
switch (id)
|
||||||
{
|
{
|
||||||
case PARAM_VERSION:
|
case PARAM_VERSION:
|
||||||
case PARAM_CONFIG_OK:
|
case PARAM_CONFIG_OK:
|
||||||
case PARAM_USE_EEPROM:
|
case PARAM_USE_EEPROM:
|
||||||
case MOVEMENT_TIMEOUT_X:
|
case MOVEMENT_TIMEOUT_X:
|
||||||
case MOVEMENT_TIMEOUT_Y:
|
case MOVEMENT_TIMEOUT_Y:
|
||||||
case MOVEMENT_TIMEOUT_Z:
|
case MOVEMENT_TIMEOUT_Z:
|
||||||
case MOVEMENT_ENABLE_ENDPOINTS_X:
|
case MOVEMENT_ENABLE_ENDPOINTS_X:
|
||||||
case MOVEMENT_ENABLE_ENDPOINTS_Y:
|
case MOVEMENT_ENABLE_ENDPOINTS_Y:
|
||||||
case MOVEMENT_ENABLE_ENDPOINTS_Z:
|
case MOVEMENT_ENABLE_ENDPOINTS_Z:
|
||||||
case MOVEMENT_INVERT_ENDPOINTS_X:
|
case MOVEMENT_INVERT_ENDPOINTS_X:
|
||||||
case MOVEMENT_INVERT_ENDPOINTS_Y:
|
case MOVEMENT_INVERT_ENDPOINTS_Y:
|
||||||
case MOVEMENT_INVERT_ENDPOINTS_Z:
|
case MOVEMENT_INVERT_ENDPOINTS_Z:
|
||||||
case MOVEMENT_INVERT_MOTOR_X:
|
case MOVEMENT_INVERT_MOTOR_X:
|
||||||
case MOVEMENT_INVERT_MOTOR_Y:
|
case MOVEMENT_INVERT_MOTOR_Y:
|
||||||
case MOVEMENT_INVERT_MOTOR_Z:
|
case MOVEMENT_INVERT_MOTOR_Z:
|
||||||
case MOVEMENT_SECONDARY_MOTOR_X:
|
case MOVEMENT_SECONDARY_MOTOR_X:
|
||||||
case MOVEMENT_SECONDARY_MOTOR_INVERT_X:
|
case MOVEMENT_SECONDARY_MOTOR_INVERT_X:
|
||||||
case MOVEMENT_STEPS_ACC_DEC_X:
|
case MOVEMENT_STEPS_ACC_DEC_X:
|
||||||
case MOVEMENT_STEPS_ACC_DEC_Y:
|
case MOVEMENT_STEPS_ACC_DEC_Y:
|
||||||
case MOVEMENT_STEPS_ACC_DEC_Z:
|
case MOVEMENT_STEPS_ACC_DEC_Z:
|
||||||
case MOVEMENT_HOME_UP_X:
|
case MOVEMENT_HOME_UP_X:
|
||||||
case MOVEMENT_HOME_UP_Y:
|
case MOVEMENT_HOME_UP_Y:
|
||||||
case MOVEMENT_HOME_UP_Z:
|
case MOVEMENT_HOME_UP_Z:
|
||||||
case MOVEMENT_MIN_SPD_X:
|
case MOVEMENT_MIN_SPD_X:
|
||||||
case MOVEMENT_MIN_SPD_Y:
|
case MOVEMENT_MIN_SPD_Y:
|
||||||
case MOVEMENT_MIN_SPD_Z:
|
case MOVEMENT_MIN_SPD_Z:
|
||||||
case MOVEMENT_MAX_SPD_X:
|
case MOVEMENT_MAX_SPD_X:
|
||||||
case MOVEMENT_MAX_SPD_Y:
|
case MOVEMENT_MAX_SPD_Y:
|
||||||
case MOVEMENT_MAX_SPD_Z:
|
case MOVEMENT_MAX_SPD_Z:
|
||||||
case ENCODER_ENABLED_X:
|
case ENCODER_ENABLED_X:
|
||||||
case ENCODER_ENABLED_Y:
|
case ENCODER_ENABLED_Y:
|
||||||
case ENCODER_ENABLED_Z:
|
case ENCODER_ENABLED_Z:
|
||||||
case ENCODER_TYPE_X:
|
case ENCODER_TYPE_X:
|
||||||
case ENCODER_TYPE_Y:
|
case ENCODER_TYPE_Y:
|
||||||
case ENCODER_TYPE_Z:
|
case ENCODER_TYPE_Z:
|
||||||
case ENCODER_MISSED_STEPS_MAX_X:
|
case ENCODER_MISSED_STEPS_MAX_X:
|
||||||
case ENCODER_MISSED_STEPS_MAX_Y:
|
case ENCODER_MISSED_STEPS_MAX_Y:
|
||||||
case ENCODER_MISSED_STEPS_MAX_Z:
|
case ENCODER_MISSED_STEPS_MAX_Z:
|
||||||
case ENCODER_SCALING_X:
|
case ENCODER_SCALING_X:
|
||||||
case ENCODER_SCALING_Y:
|
case ENCODER_SCALING_Y:
|
||||||
case ENCODER_SCALING_Z:
|
case ENCODER_SCALING_Z:
|
||||||
case ENCODER_MISSED_STEPS_DECAY_X:
|
case ENCODER_MISSED_STEPS_DECAY_X:
|
||||||
case ENCODER_MISSED_STEPS_DECAY_Y:
|
case ENCODER_MISSED_STEPS_DECAY_Y:
|
||||||
case ENCODER_MISSED_STEPS_DECAY_Z:
|
case ENCODER_MISSED_STEPS_DECAY_Z:
|
||||||
case PIN_GUARD_1_PIN_NR:
|
case PIN_GUARD_1_PIN_NR:
|
||||||
case PIN_GUARD_1_TIME_OUT:
|
case PIN_GUARD_1_TIME_OUT:
|
||||||
case PIN_GUARD_1_ACTIVE_STATE:
|
case PIN_GUARD_1_ACTIVE_STATE:
|
||||||
case PIN_GUARD_2_PIN_NR:
|
case PIN_GUARD_2_PIN_NR:
|
||||||
case PIN_GUARD_2_TIME_OUT:
|
case PIN_GUARD_2_TIME_OUT:
|
||||||
case PIN_GUARD_2_ACTIVE_STATE:
|
case PIN_GUARD_2_ACTIVE_STATE:
|
||||||
case PIN_GUARD_3_PIN_NR:
|
case PIN_GUARD_3_PIN_NR:
|
||||||
case PIN_GUARD_3_TIME_OUT:
|
case PIN_GUARD_3_TIME_OUT:
|
||||||
case PIN_GUARD_3_ACTIVE_STATE:
|
case PIN_GUARD_3_ACTIVE_STATE:
|
||||||
case PIN_GUARD_4_PIN_NR:
|
case PIN_GUARD_4_PIN_NR:
|
||||||
case PIN_GUARD_4_TIME_OUT:
|
case PIN_GUARD_4_TIME_OUT:
|
||||||
case PIN_GUARD_4_ACTIVE_STATE:
|
case PIN_GUARD_4_ACTIVE_STATE:
|
||||||
case PIN_GUARD_5_PIN_NR:
|
case PIN_GUARD_5_PIN_NR:
|
||||||
case PIN_GUARD_5_TIME_OUT:
|
case PIN_GUARD_5_TIME_OUT:
|
||||||
case PIN_GUARD_5_ACTIVE_STATE:
|
case PIN_GUARD_5_ACTIVE_STATE:
|
||||||
return true;
|
return true;
|
||||||
default:
|
default:
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -9,98 +9,96 @@
|
||||||
//#define NULL 0
|
//#define NULL 0
|
||||||
const int PARAM_NR_OF_PARAMS = 225;
|
const int PARAM_NR_OF_PARAMS = 225;
|
||||||
|
|
||||||
|
|
||||||
enum ParamListEnum
|
enum ParamListEnum
|
||||||
{
|
{
|
||||||
PARAM_VERSION = 0,
|
PARAM_VERSION = 0,
|
||||||
PARAM_TEST = 1,
|
PARAM_TEST = 1,
|
||||||
PARAM_CONFIG_OK = 2,
|
PARAM_CONFIG_OK = 2,
|
||||||
PARAM_USE_EEPROM = 3,
|
PARAM_USE_EEPROM = 3,
|
||||||
|
|
||||||
// stepper motor settings
|
// stepper motor settings
|
||||||
|
|
||||||
MOVEMENT_TIMEOUT_X = 11,
|
MOVEMENT_TIMEOUT_X = 11,
|
||||||
MOVEMENT_TIMEOUT_Y = 12,
|
MOVEMENT_TIMEOUT_Y = 12,
|
||||||
MOVEMENT_TIMEOUT_Z = 13,
|
MOVEMENT_TIMEOUT_Z = 13,
|
||||||
|
|
||||||
MOVEMENT_INVERT_ENDPOINTS_X = 21,
|
MOVEMENT_INVERT_ENDPOINTS_X = 21,
|
||||||
MOVEMENT_INVERT_ENDPOINTS_Y = 22,
|
MOVEMENT_INVERT_ENDPOINTS_Y = 22,
|
||||||
MOVEMENT_INVERT_ENDPOINTS_Z = 23,
|
MOVEMENT_INVERT_ENDPOINTS_Z = 23,
|
||||||
|
|
||||||
MOVEMENT_ENABLE_ENDPOINTS_X = 25,
|
MOVEMENT_ENABLE_ENDPOINTS_X = 25,
|
||||||
MOVEMENT_ENABLE_ENDPOINTS_Y = 26,
|
MOVEMENT_ENABLE_ENDPOINTS_Y = 26,
|
||||||
MOVEMENT_ENABLE_ENDPOINTS_Z = 27,
|
MOVEMENT_ENABLE_ENDPOINTS_Z = 27,
|
||||||
|
|
||||||
MOVEMENT_INVERT_MOTOR_X = 31,
|
MOVEMENT_INVERT_MOTOR_X = 31,
|
||||||
MOVEMENT_INVERT_MOTOR_Y = 32,
|
MOVEMENT_INVERT_MOTOR_Y = 32,
|
||||||
MOVEMENT_INVERT_MOTOR_Z = 33,
|
MOVEMENT_INVERT_MOTOR_Z = 33,
|
||||||
|
|
||||||
MOVEMENT_SECONDARY_MOTOR_X = 36,
|
MOVEMENT_SECONDARY_MOTOR_X = 36,
|
||||||
MOVEMENT_SECONDARY_MOTOR_INVERT_X = 37,
|
MOVEMENT_SECONDARY_MOTOR_INVERT_X = 37,
|
||||||
|
|
||||||
MOVEMENT_STEPS_ACC_DEC_X = 41,
|
MOVEMENT_STEPS_ACC_DEC_X = 41,
|
||||||
MOVEMENT_STEPS_ACC_DEC_Y = 42,
|
MOVEMENT_STEPS_ACC_DEC_Y = 42,
|
||||||
MOVEMENT_STEPS_ACC_DEC_Z = 43,
|
MOVEMENT_STEPS_ACC_DEC_Z = 43,
|
||||||
|
|
||||||
MOVEMENT_HOME_UP_X = 51,
|
MOVEMENT_HOME_UP_X = 51,
|
||||||
MOVEMENT_HOME_UP_Y = 52,
|
MOVEMENT_HOME_UP_Y = 52,
|
||||||
MOVEMENT_HOME_UP_Z = 53,
|
MOVEMENT_HOME_UP_Z = 53,
|
||||||
|
|
||||||
MOVEMENT_MIN_SPD_X = 61,
|
MOVEMENT_MIN_SPD_X = 61,
|
||||||
MOVEMENT_MIN_SPD_Y = 62,
|
MOVEMENT_MIN_SPD_Y = 62,
|
||||||
MOVEMENT_MIN_SPD_Z = 63,
|
MOVEMENT_MIN_SPD_Z = 63,
|
||||||
|
|
||||||
MOVEMENT_MAX_SPD_X = 71,
|
MOVEMENT_MAX_SPD_X = 71,
|
||||||
MOVEMENT_MAX_SPD_Y = 72,
|
MOVEMENT_MAX_SPD_Y = 72,
|
||||||
MOVEMENT_MAX_SPD_Z = 73,
|
MOVEMENT_MAX_SPD_Z = 73,
|
||||||
|
|
||||||
// encoder settings
|
// encoder settings
|
||||||
ENCODER_ENABLED_X = 101,
|
ENCODER_ENABLED_X = 101,
|
||||||
ENCODER_ENABLED_Y = 102,
|
ENCODER_ENABLED_Y = 102,
|
||||||
ENCODER_ENABLED_Z = 103,
|
ENCODER_ENABLED_Z = 103,
|
||||||
|
|
||||||
ENCODER_TYPE_X = 105,
|
ENCODER_TYPE_X = 105,
|
||||||
ENCODER_TYPE_Y = 106,
|
ENCODER_TYPE_Y = 106,
|
||||||
ENCODER_TYPE_Z = 107,
|
ENCODER_TYPE_Z = 107,
|
||||||
|
|
||||||
ENCODER_MISSED_STEPS_MAX_X = 111,
|
ENCODER_MISSED_STEPS_MAX_X = 111,
|
||||||
ENCODER_MISSED_STEPS_MAX_Y = 112,
|
ENCODER_MISSED_STEPS_MAX_Y = 112,
|
||||||
ENCODER_MISSED_STEPS_MAX_Z = 113,
|
ENCODER_MISSED_STEPS_MAX_Z = 113,
|
||||||
|
|
||||||
ENCODER_SCALING_X = 115,
|
ENCODER_SCALING_X = 115,
|
||||||
ENCODER_SCALING_Y = 116,
|
ENCODER_SCALING_Y = 116,
|
||||||
ENCODER_SCALING_Z = 117,
|
ENCODER_SCALING_Z = 117,
|
||||||
|
|
||||||
ENCODER_MISSED_STEPS_DECAY_X = 121,
|
ENCODER_MISSED_STEPS_DECAY_X = 121,
|
||||||
ENCODER_MISSED_STEPS_DECAY_Y = 122,
|
ENCODER_MISSED_STEPS_DECAY_Y = 122,
|
||||||
ENCODER_MISSED_STEPS_DECAY_Z = 123,
|
ENCODER_MISSED_STEPS_DECAY_Z = 123,
|
||||||
|
|
||||||
// not used in software at this time
|
// not used in software at this time
|
||||||
MOVEMENT_AXIS_NR_STEPS_X = 141,
|
MOVEMENT_AXIS_NR_STEPS_X = 141,
|
||||||
MOVEMENT_AXIS_NR_STEPS_Y = 142,
|
MOVEMENT_AXIS_NR_STEPS_Y = 142,
|
||||||
MOVEMENT_AXIS_NR_STEPS_Z = 143,
|
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_2_PIN_NR = 205,
|
||||||
PIN_GUARD_1_PIN_NR = 201,
|
PIN_GUARD_2_TIME_OUT = 206,
|
||||||
PIN_GUARD_1_TIME_OUT = 202,
|
PIN_GUARD_2_ACTIVE_STATE = 207,
|
||||||
PIN_GUARD_1_ACTIVE_STATE = 203,
|
|
||||||
|
|
||||||
PIN_GUARD_2_PIN_NR = 205,
|
PIN_GUARD_3_PIN_NR = 211,
|
||||||
PIN_GUARD_2_TIME_OUT = 206,
|
PIN_GUARD_3_TIME_OUT = 212,
|
||||||
PIN_GUARD_2_ACTIVE_STATE = 207,
|
PIN_GUARD_3_ACTIVE_STATE = 213,
|
||||||
|
|
||||||
PIN_GUARD_3_PIN_NR = 211,
|
PIN_GUARD_4_PIN_NR = 215,
|
||||||
PIN_GUARD_3_TIME_OUT = 212,
|
PIN_GUARD_4_TIME_OUT = 216,
|
||||||
PIN_GUARD_3_ACTIVE_STATE = 213,
|
PIN_GUARD_4_ACTIVE_STATE = 217,
|
||||||
|
|
||||||
PIN_GUARD_4_PIN_NR = 215,
|
PIN_GUARD_5_PIN_NR = 221,
|
||||||
PIN_GUARD_4_TIME_OUT = 216,
|
PIN_GUARD_5_TIME_OUT = 222,
|
||||||
PIN_GUARD_4_ACTIVE_STATE = 217,
|
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
|
#define NULL 0
|
||||||
*/
|
*/
|
||||||
|
|
||||||
class ParameterList {
|
class ParameterList
|
||||||
ParamListEnum paramListEnum;
|
{
|
||||||
|
ParamListEnum paramListEnum;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
static ParameterList* getInstance();
|
static ParameterList *getInstance();
|
||||||
int writeValue(int id, int value);
|
int writeValue(int id, int value);
|
||||||
int readValue(int id);
|
int readValue(int id);
|
||||||
int getValue(int id);
|
int getValue(int id);
|
||||||
|
|
||||||
bool validParam(int id);
|
bool validParam(int id);
|
||||||
void loadDefaultValue(int id);
|
void loadDefaultValue(int id);
|
||||||
|
|
||||||
int readAllValues();
|
int readAllValues();
|
||||||
int readAllValuesFromEeprom();
|
int readAllValuesFromEeprom();
|
||||||
int writeAllValuesToEeprom();
|
int writeAllValuesToEeprom();
|
||||||
int setAllValuesToDefault();
|
int setAllValuesToDefault();
|
||||||
|
|
||||||
int readValueEeprom(int id);
|
int readValueEeprom(int id);
|
||||||
int writeValueEeprom(int id, int value);
|
int writeValueEeprom(int id, int value);
|
||||||
|
|
||||||
void sendConfigToModules();
|
void sendConfigToModules();
|
||||||
|
|
||||||
int paramChangeNumber();
|
int paramChangeNumber();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
ParameterList();
|
ParameterList();
|
||||||
ParameterList(ParameterList const&);
|
ParameterList(ParameterList const &);
|
||||||
void operator=(ParameterList const&);
|
void operator=(ParameterList const &);
|
||||||
|
|
||||||
int paramChangeNr;
|
|
||||||
|
|
||||||
|
int paramChangeNr;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif /* PARAMETERLIST_H_ */
|
#endif /* PARAMETERLIST_H_ */
|
||||||
|
|
|
@ -1,71 +1,84 @@
|
||||||
|
|
||||||
#include "PinControl.h"
|
#include "PinControl.h"
|
||||||
|
|
||||||
static PinControl* instance;
|
static PinControl *instance;
|
||||||
|
|
||||||
PinControl * PinControl::getInstance() {
|
PinControl *PinControl::getInstance()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new PinControl();
|
if (!instance)
|
||||||
};
|
{
|
||||||
return instance;
|
instance = new PinControl();
|
||||||
}
|
};
|
||||||
;
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
PinControl::PinControl() {
|
PinControl::PinControl()
|
||||||
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
int PinControl::setMode(int pinNr, int mode) {
|
int PinControl::setMode(int pinNr, int mode)
|
||||||
pinMode(pinNr , mode );
|
{
|
||||||
return 0;
|
pinMode(pinNr, mode);
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
int PinControl::writeValue(int pinNr, int value, int mode) {
|
int PinControl::writeValue(int pinNr, int value, int mode)
|
||||||
if (mode == 0) {
|
{
|
||||||
digitalWrite(pinNr, value);
|
if (mode == 0)
|
||||||
return 0;
|
{
|
||||||
}
|
digitalWrite(pinNr, value);
|
||||||
if (mode == 1) {
|
return 0;
|
||||||
analogWrite(pinNr, value);
|
}
|
||||||
return 0;
|
if (mode == 1)
|
||||||
}
|
{
|
||||||
return 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 (mode == 0)
|
||||||
if (digitalRead(pinNr) == 1){
|
{
|
||||||
value = 1;
|
if (digitalRead(pinNr) == 1)
|
||||||
}
|
{
|
||||||
}
|
value = 1;
|
||||||
if (mode == 1) {
|
}
|
||||||
value = analogRead(pinNr);
|
}
|
||||||
}
|
if (mode == 1)
|
||||||
|
{
|
||||||
|
value = analogRead(pinNr);
|
||||||
|
}
|
||||||
|
|
||||||
if (mode == 0 || mode == 1) {
|
if (mode == 0 || mode == 1)
|
||||||
|
{
|
||||||
|
|
||||||
Serial.print("R41");
|
Serial.print("R41");
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
Serial.print("P");
|
Serial.print("P");
|
||||||
Serial.print(pinNr);
|
Serial.print(pinNr);
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
Serial.print("V");
|
Serial.print("V");
|
||||||
Serial.print(value);
|
Serial.print(value);
|
||||||
//Serial.print("\r\n");
|
//Serial.print("\r\n");
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
return 1;
|
{
|
||||||
}
|
return 1;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int PinControl::writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode) {
|
int PinControl::writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode)
|
||||||
writeValue( pinNr, valueOne, mode);
|
{
|
||||||
delay(time);
|
writeValue(pinNr, valueOne, mode);
|
||||||
writeValue( pinNr, valueTwo, mode);
|
delay(time);
|
||||||
return 0;
|
writeValue(pinNr, valueTwo, mode);
|
||||||
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
|
@ -16,19 +16,20 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include "CurrentState.h"
|
#include "CurrentState.h"
|
||||||
|
|
||||||
class PinControl {
|
class PinControl
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static PinControl* getInstance();
|
static PinControl *getInstance();
|
||||||
|
|
||||||
int setMode(int pinNr, int mode);
|
int setMode(int pinNr, int mode);
|
||||||
int writeValue(int pinNr, int value, int mode);
|
int writeValue(int pinNr, int value, int mode);
|
||||||
int readValue(int pinNr, int mode);
|
int readValue(int pinNr, int mode);
|
||||||
int writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode);
|
int writePulse(int pinNr, int valueOne, int valueTwo, long time, int mode);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
PinControl();
|
PinControl();
|
||||||
PinControl(PinControl const&);
|
PinControl(PinControl const &);
|
||||||
void operator=(PinControl const&);
|
void operator=(PinControl const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* PINCONTROL_H_ */
|
#endif /* PINCONTROL_H_ */
|
||||||
|
|
|
@ -1,39 +1,42 @@
|
||||||
|
|
||||||
#include "PinGuard.h"
|
#include "PinGuard.h"
|
||||||
|
|
||||||
static PinGuard* instance;
|
static PinGuard *instance;
|
||||||
|
|
||||||
PinGuard * PinGuard::getInstance() {
|
PinGuard *PinGuard::getInstance()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new PinGuard();
|
if (!instance)
|
||||||
};
|
{
|
||||||
return instance;
|
instance = new PinGuard();
|
||||||
}
|
};
|
||||||
;
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
PinGuard::PinGuard() {
|
PinGuard::PinGuard()
|
||||||
|
{
|
||||||
pinGuardPin[0] = PinGuardPin();
|
|
||||||
pinGuardPin[1] = PinGuardPin();
|
|
||||||
pinGuardPin[2] = PinGuardPin();
|
|
||||||
pinGuardPin[3] = PinGuardPin();
|
|
||||||
pinGuardPin[4] = PinGuardPin();
|
|
||||||
loadConfig();
|
|
||||||
|
|
||||||
|
pinGuardPin[0] = PinGuardPin();
|
||||||
|
pinGuardPin[1] = PinGuardPin();
|
||||||
|
pinGuardPin[2] = PinGuardPin();
|
||||||
|
pinGuardPin[3] = PinGuardPin();
|
||||||
|
pinGuardPin[4] = PinGuardPin();
|
||||||
|
loadConfig();
|
||||||
}
|
}
|
||||||
|
|
||||||
void PinGuard::loadConfig() {
|
void PinGuard::loadConfig()
|
||||||
pinGuardPin[0].loadPinConfig(PIN_GUARD_1_PIN_NR, PIN_GUARD_1_ACTIVE_STATE, PIN_GUARD_1_TIME_OUT);
|
{
|
||||||
pinGuardPin[1].loadPinConfig(PIN_GUARD_2_PIN_NR, PIN_GUARD_2_ACTIVE_STATE, PIN_GUARD_2_TIME_OUT);
|
pinGuardPin[0].loadPinConfig(PIN_GUARD_1_PIN_NR, PIN_GUARD_1_ACTIVE_STATE, PIN_GUARD_1_TIME_OUT);
|
||||||
pinGuardPin[2].loadPinConfig(PIN_GUARD_3_PIN_NR, PIN_GUARD_3_ACTIVE_STATE, PIN_GUARD_3_TIME_OUT);
|
pinGuardPin[1].loadPinConfig(PIN_GUARD_2_PIN_NR, PIN_GUARD_2_ACTIVE_STATE, PIN_GUARD_2_TIME_OUT);
|
||||||
pinGuardPin[3].loadPinConfig(PIN_GUARD_4_PIN_NR, PIN_GUARD_4_ACTIVE_STATE, PIN_GUARD_4_TIME_OUT);
|
pinGuardPin[2].loadPinConfig(PIN_GUARD_3_PIN_NR, PIN_GUARD_3_ACTIVE_STATE, PIN_GUARD_3_TIME_OUT);
|
||||||
pinGuardPin[4].loadPinConfig(PIN_GUARD_5_PIN_NR, PIN_GUARD_5_ACTIVE_STATE, PIN_GUARD_5_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() {
|
void PinGuard::checkPins()
|
||||||
pinGuardPin[0].processTick();
|
{
|
||||||
pinGuardPin[1].processTick();
|
pinGuardPin[0].processTick();
|
||||||
pinGuardPin[2].processTick();
|
pinGuardPin[1].processTick();
|
||||||
pinGuardPin[3].processTick();
|
pinGuardPin[2].processTick();
|
||||||
pinGuardPin[4].processTick();
|
pinGuardPin[3].processTick();
|
||||||
|
pinGuardPin[4].processTick();
|
||||||
}
|
}
|
||||||
|
|
|
@ -17,27 +17,26 @@
|
||||||
#include "PinGuardPin.h"
|
#include "PinGuardPin.h"
|
||||||
#include "ParameterList.h"
|
#include "ParameterList.h"
|
||||||
|
|
||||||
class PinGuard {
|
class PinGuard
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static PinGuard* getInstance();
|
static PinGuard *getInstance();
|
||||||
|
|
||||||
void loadConfig();
|
void loadConfig();
|
||||||
void checkPins();
|
void checkPins();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
//long pinTimeOut[100];
|
||||||
|
//long pinCurrentTime[100];
|
||||||
|
//void checkPin;
|
||||||
|
//bool pinSafeState[100];
|
||||||
|
|
||||||
|
PinGuardPin pinGuardPin[5];
|
||||||
|
//PinGuardPin test;
|
||||||
|
|
||||||
//long pinTimeOut[100];
|
PinGuard();
|
||||||
//long pinCurrentTime[100];
|
PinGuard(PinGuard const &);
|
||||||
//void checkPin;
|
void operator=(PinGuard const &);
|
||||||
//bool pinSafeState[100];
|
|
||||||
|
|
||||||
PinGuardPin pinGuardPin[5];
|
|
||||||
//PinGuardPin test;
|
|
||||||
|
|
||||||
PinGuard();
|
|
||||||
PinGuard(PinGuard const&);
|
|
||||||
void operator=(PinGuard const&);
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* PINGUARD_H_ */
|
#endif /* PINGUARD_H_ */
|
||||||
|
|
|
@ -2,38 +2,44 @@
|
||||||
#include "PinGuardPin.h"
|
#include "PinGuardPin.h"
|
||||||
#include "ParameterList.h"
|
#include "ParameterList.h"
|
||||||
|
|
||||||
PinGuardPin::PinGuardPin() {
|
PinGuardPin::PinGuardPin()
|
||||||
pinNr = 0;
|
{
|
||||||
|
pinNr = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the initial settings for what pin to check
|
// 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);
|
pinNr = ParameterList::getInstance()->getValue(pinNrParamNr);
|
||||||
activeState = (ParameterList::getInstance()->getValue(activeStateParamNr)== 1);
|
activeState = (ParameterList::getInstance()->getValue(activeStateParamNr) == 1);
|
||||||
timeOut = ParameterList::getInstance()->getValue(timeOutParamNr);
|
timeOut = ParameterList::getInstance()->getValue(timeOutParamNr);
|
||||||
|
|
||||||
timeOutCount = 0;
|
timeOutCount = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Check each second if the time out is lapsed or the value has changed
|
// Check each second if the time out is lapsed or the value has changed
|
||||||
void PinGuardPin::processTick() {
|
void PinGuardPin::processTick()
|
||||||
|
{
|
||||||
|
|
||||||
if (pinNr==0) {
|
if (pinNr == 0)
|
||||||
return;
|
{
|
||||||
}
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
currentStatePin = digitalRead(pinNr);
|
currentStatePin = digitalRead(pinNr);
|
||||||
|
|
||||||
if (currentStatePin != activeState) {
|
if (currentStatePin != activeState)
|
||||||
timeOutCount = 0;
|
{
|
||||||
} else {
|
timeOutCount = 0;
|
||||||
timeOutCount++;
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
timeOutCount++;
|
||||||
|
}
|
||||||
|
|
||||||
if (timeOutCount >= timeOut) {
|
if (timeOutCount >= timeOut)
|
||||||
digitalWrite(pinNr, !activeState);
|
{
|
||||||
}
|
digitalWrite(pinNr, !activeState);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -16,23 +16,23 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
//#include "ParameterList.h"
|
//#include "ParameterList.h"
|
||||||
|
|
||||||
class PinGuardPin {
|
class PinGuardPin
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
|
PinGuardPin();
|
||||||
|
|
||||||
PinGuardPin();
|
void processTick();
|
||||||
|
void loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr);
|
||||||
|
|
||||||
void processTick();
|
|
||||||
void loadPinConfig(int pinNrParamNr, int activeStateParamNr, int timeOutParamNr);
|
|
||||||
private:
|
private:
|
||||||
//PinControlPin(PinControlPin const&);
|
//PinControlPin(PinControlPin const&);
|
||||||
///void operator=(PinControlPin const&);
|
///void operator=(PinControlPin const&);
|
||||||
|
|
||||||
int pinNr;
|
|
||||||
long timeOut;
|
|
||||||
long timeOutCount;
|
|
||||||
bool activeState;
|
|
||||||
bool currentStatePin;
|
|
||||||
|
|
||||||
|
int pinNr;
|
||||||
|
long timeOut;
|
||||||
|
long timeOutCount;
|
||||||
|
bool activeState;
|
||||||
|
bool currentStatePin;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* PINGUARDPIN_H_ */
|
#endif /* PINGUARDPIN_H_ */
|
||||||
|
|
|
@ -7,29 +7,33 @@ Servo pin layout
|
||||||
D11 D6 D5 D4
|
D11 D6 D5 D4
|
||||||
*/
|
*/
|
||||||
|
|
||||||
static ServoControl* instance;
|
static ServoControl *instance;
|
||||||
|
|
||||||
Servo servos[2];
|
Servo servos[2];
|
||||||
|
|
||||||
ServoControl * ServoControl::getInstance() {
|
ServoControl *ServoControl::getInstance()
|
||||||
if (!instance) {
|
{
|
||||||
instance = new ServoControl();
|
if (!instance)
|
||||||
};
|
{
|
||||||
return instance;
|
instance = new ServoControl();
|
||||||
}
|
};
|
||||||
;
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
ServoControl::ServoControl() {
|
ServoControl::ServoControl()
|
||||||
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
int ServoControl::attach() {
|
int ServoControl::attach()
|
||||||
servos[0].attach(SERVO_0_PIN);
|
{
|
||||||
servos[1].attach(SERVO_1_PIN);
|
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("R99");
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
Serial.print("SERVO");
|
Serial.print("SERVO");
|
||||||
|
@ -45,19 +49,17 @@ int ServoControl::setAngle(int pin, int angle) {
|
||||||
Serial.print("\r\n");
|
Serial.print("\r\n");
|
||||||
*/
|
*/
|
||||||
|
|
||||||
switch(pin) {
|
switch (pin)
|
||||||
case 4:
|
{
|
||||||
servos[0].write(angle);
|
case 4:
|
||||||
break;
|
servos[0].write(angle);
|
||||||
case 5:
|
break;
|
||||||
servos[1].write(angle);
|
case 5:
|
||||||
break;
|
servos[1].write(angle);
|
||||||
default:
|
break;
|
||||||
return 1;
|
default:
|
||||||
}
|
return 1;
|
||||||
|
}
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -14,16 +14,18 @@
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
class ServoControl {
|
class ServoControl
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
static ServoControl* getInstance();
|
static ServoControl *getInstance();
|
||||||
|
|
||||||
|
int attach();
|
||||||
|
int setAngle(int pin, int angle);
|
||||||
|
|
||||||
int attach();
|
|
||||||
int setAngle(int pin, int angle);
|
|
||||||
private:
|
private:
|
||||||
ServoControl();
|
ServoControl();
|
||||||
ServoControl(ServoControl const&);
|
ServoControl(ServoControl const &);
|
||||||
void operator=(ServoControl const&);
|
void operator=(ServoControl const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* SERVOCONTROL_H_ */
|
#endif /* SERVOCONTROL_H_ */
|
||||||
|
|
|
@ -1,50 +1,49 @@
|
||||||
#include "StatusList.h"
|
#include "StatusList.h"
|
||||||
|
|
||||||
static StatusList* instanceParam;
|
static StatusList *instanceParam;
|
||||||
long statusValues[150];
|
long statusValues[150];
|
||||||
|
|
||||||
StatusList * StatusList::getInstance() {
|
StatusList *StatusList::getInstance()
|
||||||
if (!instanceParam) {
|
{
|
||||||
instanceParam = new StatusList();
|
if (!instanceParam)
|
||||||
};
|
{
|
||||||
return 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_X] = MOVEMENT_MAX_SPD_X_DEFAULT;
|
//paramValues[MOVEMENT_MAX_SPD_Z] = MOVEMENT_MAX_SPD_Z_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();
|
||||||
|
|
||||||
|
return 0;
|
||||||
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;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
long StatusList::getValue(int id)
|
||||||
|
{
|
||||||
|
|
||||||
long StatusList::getValue(int id) {
|
/*
|
||||||
|
|
||||||
/*
|
|
||||||
Serial.print("R99");
|
Serial.print("R99");
|
||||||
Serial.print(" ");
|
Serial.print(" ");
|
||||||
Serial.print("getValue");
|
Serial.print("getValue");
|
||||||
|
@ -55,13 +54,13 @@ long StatusList::getValue(int id) {
|
||||||
Serial.print("\r\n");
|
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -7,14 +7,13 @@
|
||||||
|
|
||||||
//#define NULL 0
|
//#define NULL 0
|
||||||
|
|
||||||
|
|
||||||
enum StatusListEnum
|
enum StatusListEnum
|
||||||
{
|
{
|
||||||
STATUS_GENERAL = 0,
|
STATUS_GENERAL = 0,
|
||||||
|
|
||||||
//MOVEMENT_MAX_SPD_X = 71,
|
//MOVEMENT_MAX_SPD_X = 71,
|
||||||
//MOVEMENT_MAX_SPD_Y = 72,
|
//MOVEMENT_MAX_SPD_Y = 72,
|
||||||
//MOVEMENT_MAX_SPD_Z = 73
|
//MOVEMENT_MAX_SPD_Z = 73
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -22,19 +21,21 @@ enum StatusListEnum
|
||||||
#define NULL 0
|
#define NULL 0
|
||||||
*/
|
*/
|
||||||
|
|
||||||
class StatusList {
|
class StatusList
|
||||||
StatusListEnum statusListEnum;
|
{
|
||||||
|
StatusListEnum statusListEnum;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
static StatusList* getInstance();
|
static StatusList *getInstance();
|
||||||
int writeValue(int id, long value);
|
int writeValue(int id, long value);
|
||||||
int readValue(int id);
|
int readValue(int id);
|
||||||
long getValue(int id);
|
long getValue(int id);
|
||||||
int setValue(int id, long value);
|
int setValue(int id, long value);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
StatusList();
|
StatusList();
|
||||||
StatusList(StatusList const&);
|
StatusList(StatusList const &);
|
||||||
void operator=(StatusList const&);
|
void operator=(StatusList const &);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
#endif /* STATUSLIST_H_ */
|
#endif /* STATUSLIST_H_ */
|
||||||
|
|
File diff suppressed because it is too large
Load Diff
|
@ -19,87 +19,87 @@
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include "Command.h"
|
#include "Command.h"
|
||||||
|
|
||||||
class StepperControl {
|
class StepperControl
|
||||||
|
{
|
||||||
public:
|
public:
|
||||||
StepperControl();
|
StepperControl();
|
||||||
StepperControl(StepperControl const&);
|
StepperControl(StepperControl const &);
|
||||||
void operator=(StepperControl const&);
|
void operator=(StepperControl const &);
|
||||||
|
|
||||||
static StepperControl* getInstance();
|
static StepperControl *getInstance();
|
||||||
//int moveAbsolute( long xDest, long yDest,long zDest,
|
//int moveAbsolute( long xDest, long yDest,long zDest,
|
||||||
// unsigned int maxStepsPerSecond,
|
// unsigned int maxStepsPerSecond,
|
||||||
// unsigned int maxAccelerationStepsPerSecond);
|
// unsigned int maxAccelerationStepsPerSecond);
|
||||||
int moveToCoords( long xDest, long yDest, long zDest,
|
int moveToCoords(long xDest, long yDest, long zDest,
|
||||||
unsigned int xMaxSpd, unsigned int yMaxSpd, unsigned int zMaxSpd,
|
unsigned int xMaxSpd, unsigned int yMaxSpd, unsigned int zMaxSpd,
|
||||||
bool homeX, bool homeY, bool homeZ
|
bool homeX, bool homeY, bool homeZ);
|
||||||
);
|
|
||||||
|
|
||||||
void handleMovementInterrupt();
|
void handleMovementInterrupt();
|
||||||
int calibrateAxis(int axis);
|
int calibrateAxis(int axis);
|
||||||
void initInterrupt();
|
void initInterrupt();
|
||||||
void enableMotors();
|
void enableMotors();
|
||||||
void disableMotors();
|
void disableMotors();
|
||||||
bool motorsEnabled();
|
bool motorsEnabled();
|
||||||
|
|
||||||
void storePosition();
|
void storePosition();
|
||||||
void loadSettings();
|
void loadSettings();
|
||||||
|
|
||||||
void setPositionX(long pos);
|
void setPositionX(long pos);
|
||||||
void setPositionY(long pos);
|
void setPositionY(long pos);
|
||||||
void setPositionZ(long pos);
|
void setPositionZ(long pos);
|
||||||
|
|
||||||
void test();
|
void test();
|
||||||
void test2();
|
void test2();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
StepperControlAxis axisX;
|
StepperControlAxis axisX;
|
||||||
StepperControlAxis axisY;
|
StepperControlAxis axisY;
|
||||||
StepperControlAxis axisZ;
|
StepperControlAxis axisZ;
|
||||||
|
|
||||||
StepperControlEncoder encoderX;
|
StepperControlEncoder encoderX;
|
||||||
StepperControlEncoder encoderY;
|
StepperControlEncoder encoderY;
|
||||||
StepperControlEncoder encoderZ;
|
StepperControlEncoder encoderZ;
|
||||||
|
|
||||||
void checkAxisVsEncoder(StepperControlAxis* axis, StepperControlEncoder* encoder, float* missedSteps, long* lastPosition, float* encoderStepDecay, bool* encoderEnabled);
|
void checkAxisVsEncoder(StepperControlAxis *axis, StepperControlEncoder *encoder, float *missedSteps, long *lastPosition, float *encoderStepDecay, bool *encoderEnabled);
|
||||||
void checkAxisSubStatus(StepperControlAxis* axis, int* axisSubStatus);
|
void checkAxisSubStatus(StepperControlAxis *axis, int *axisSubStatus);
|
||||||
|
|
||||||
bool axisActive[3];
|
bool axisActive[3];
|
||||||
int axisSubStep[3];
|
int axisSubStep[3];
|
||||||
|
|
||||||
void loadMotorSettings();
|
void loadMotorSettings();
|
||||||
void loadEncoderSettings();
|
void loadEncoderSettings();
|
||||||
bool intToBool(int value);
|
bool intToBool(int value);
|
||||||
|
|
||||||
void reportPosition();
|
void reportPosition();
|
||||||
void storeEndStops();
|
void storeEndStops();
|
||||||
void reportEndStops();
|
void reportEndStops();
|
||||||
void reportStatus(StepperControlAxis* axis, int axisSubStatus);
|
void reportStatus(StepperControlAxis *axis, int axisSubStatus);
|
||||||
void reportCalib(StepperControlAxis* axis, int calibStatus);
|
void reportCalib(StepperControlAxis *axis, int calibStatus);
|
||||||
|
|
||||||
unsigned long getMaxLength(unsigned long lengths[3]);
|
unsigned long getMaxLength(unsigned long lengths[3]);
|
||||||
bool endStopsReached();
|
bool endStopsReached();
|
||||||
|
|
||||||
bool homeIsUp[3];
|
bool homeIsUp[3];
|
||||||
long speedMax[3];
|
long speedMax[3];
|
||||||
long speedMin[3];
|
long speedMin[3];
|
||||||
long stepsAcc[3];
|
long stepsAcc[3];
|
||||||
bool motorInv[3];
|
bool motorInv[3];
|
||||||
bool motor2Inv[3];
|
bool motor2Inv[3];
|
||||||
bool motor2Enbl[3];
|
bool motor2Enbl[3];
|
||||||
bool endStInv[3];
|
bool endStInv[3];
|
||||||
bool endStEnbl[3];
|
bool endStEnbl[3];
|
||||||
long timeOut[3];
|
long timeOut[3];
|
||||||
|
|
||||||
float motorConsMissedSteps[3];
|
float motorConsMissedSteps[3];
|
||||||
long motorLastPosition[3];
|
long motorLastPosition[3];
|
||||||
|
|
||||||
int motorConsMissedStepsMax[3];
|
int motorConsMissedStepsMax[3];
|
||||||
float motorConsMissedStepsDecay[3];
|
float motorConsMissedStepsDecay[3];
|
||||||
bool motorConsEncoderEnabled[3];
|
bool motorConsEncoderEnabled[3];
|
||||||
int motorConsEncoderType[3];
|
int motorConsEncoderType[3];
|
||||||
int motorConsEncoderScaling[3];
|
int motorConsEncoderScaling[3];
|
||||||
|
|
||||||
bool motorMotorsEnabled;
|
bool motorMotorsEnabled;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* STEPPERCONTROL_H_ */
|
#endif /* STEPPERCONTROL_H_ */
|
||||||
|
|
|
@ -1,507 +1,611 @@
|
||||||
#include "StepperControlAxis.h"
|
#include "StepperControlAxis.h"
|
||||||
|
|
||||||
StepperControlAxis::StepperControlAxis() {
|
StepperControlAxis::StepperControlAxis()
|
||||||
lastCalcLog = 0;
|
{
|
||||||
|
lastCalcLog = 0;
|
||||||
|
|
||||||
pinStep = 0;
|
pinStep = 0;
|
||||||
pinDirection = 0;
|
pinDirection = 0;
|
||||||
pinEnable = 0;
|
pinEnable = 0;
|
||||||
|
|
||||||
pin2Step = 0;
|
pin2Step = 0;
|
||||||
pin2Direction = 0;
|
pin2Direction = 0;
|
||||||
pin2Enable = 0;
|
pin2Enable = 0;
|
||||||
|
|
||||||
pinMin = 0;
|
pinMin = 0;
|
||||||
pinMax = 0;
|
pinMax = 0;
|
||||||
|
|
||||||
axisActive = false;
|
axisActive = false;
|
||||||
|
|
||||||
coordSourcePoint = 0;
|
coordSourcePoint = 0;
|
||||||
coordCurrentPoint = 0;
|
coordCurrentPoint = 0;
|
||||||
coordDestinationPoint = 0;
|
coordDestinationPoint = 0;
|
||||||
coordHomeAxis = 0;
|
coordHomeAxis = 0;
|
||||||
|
|
||||||
movementUp = false;
|
movementUp = false;
|
||||||
movementToHome = false;
|
movementToHome = false;
|
||||||
movementAccelerating = false;
|
movementAccelerating = false;
|
||||||
movementDecelerating = false;
|
movementDecelerating = false;
|
||||||
movementCruising = false;
|
movementCruising = false;
|
||||||
movementCrawling = false;
|
movementCrawling = false;
|
||||||
movementMotorActive = false;
|
movementMotorActive = false;
|
||||||
movementMoving = false;
|
movementMoving = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::test() {
|
void StepperControlAxis::test()
|
||||||
Serial.print("R99");
|
{
|
||||||
Serial.print(" cur loc = ");
|
Serial.print("R99");
|
||||||
Serial.print(coordCurrentPoint);
|
Serial.print(" cur loc = ");
|
||||||
//Serial.print(" enc loc = ");
|
Serial.print(coordCurrentPoint);
|
||||||
//Serial.print(coordEncoderPoint);
|
//Serial.print(" enc loc = ");
|
||||||
//Serial.print(" cons steps missed = ");
|
//Serial.print(coordEncoderPoint);
|
||||||
//Serial.print(label);
|
//Serial.print(" cons steps missed = ");
|
||||||
//Serial.print(consMissedSteps);
|
//Serial.print(label);
|
||||||
Serial.print("\r\n");
|
//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 staPos;
|
||||||
long endPos;
|
long endPos;
|
||||||
|
|
||||||
|
movementAccelerating = false;
|
||||||
|
movementDecelerating = false;
|
||||||
|
movementCruising = false;
|
||||||
|
movementCrawling = false;
|
||||||
|
movementMoving = false;
|
||||||
|
|
||||||
movementAccelerating = false;
|
if (abs(sourcePosition) < abs(destinationPosition))
|
||||||
movementDecelerating = false;
|
{
|
||||||
movementCruising = false;
|
staPos = abs(sourcePosition);
|
||||||
movementCrawling = false;
|
endPos = abs(destinationPosition);
|
||||||
movementMoving = false;
|
;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
staPos = abs(destinationPosition);
|
||||||
|
;
|
||||||
|
endPos = abs(sourcePosition);
|
||||||
|
}
|
||||||
|
|
||||||
if (abs(sourcePosition) < abs(destinationPosition)) {
|
unsigned long halfway = ((endPos - staPos) / 2) + staPos;
|
||||||
staPos = abs(sourcePosition);
|
|
||||||
endPos = abs(destinationPosition);;
|
|
||||||
} else {
|
|
||||||
staPos = abs(destinationPosition);;
|
|
||||||
endPos = abs(sourcePosition);
|
|
||||||
}
|
|
||||||
|
|
||||||
unsigned long halfway = ((endPos - staPos) / 2) + staPos;
|
// Set the minimum speed if the position would be out of bounds
|
||||||
|
if (curPos < staPos || curPos > endPos)
|
||||||
|
{
|
||||||
|
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 (debugPrint && (millis() - lastCalcLog > 1000))
|
||||||
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;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
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("\r\n");
|
||||||
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(" ");
|
// Return the calculated speed, in steps per second
|
||||||
Serial.print(newSpeed);
|
return newSpeed;
|
||||||
|
|
||||||
Serial.print("\r\n");
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// Return the calculated speed, in steps per second
|
|
||||||
return newSpeed;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::checkAxisDirection() {
|
void StepperControlAxis::checkAxisDirection()
|
||||||
|
{
|
||||||
|
|
||||||
if (coordHomeAxis){
|
if (coordHomeAxis)
|
||||||
// When home is active, the direction is fixed
|
{
|
||||||
movementUp = motorHomeIsUp;
|
// When home is active, the direction is fixed
|
||||||
movementToHome = true;
|
movementUp = motorHomeIsUp;
|
||||||
} else {
|
movementToHome = true;
|
||||||
// For normal movement, move in direction of destination
|
}
|
||||||
movementUp = ( coordCurrentPoint < coordDestinationPoint );
|
else
|
||||||
movementToHome = (abs(coordCurrentPoint) >= abs(coordDestinationPoint));
|
{
|
||||||
}
|
// For normal movement, move in direction of destination
|
||||||
|
movementUp = (coordCurrentPoint < coordDestinationPoint);
|
||||||
|
movementToHome = (abs(coordCurrentPoint) >= abs(coordDestinationPoint));
|
||||||
|
}
|
||||||
|
|
||||||
if (coordCurrentPoint == 0) {
|
if (coordCurrentPoint == 0)
|
||||||
// Go slow when theoretical end point reached but there is no end stop siganl
|
{
|
||||||
axisSpeed = motorSpeedMin;
|
// Go slow when theoretical end point reached but there is no end stop siganl
|
||||||
}
|
axisSpeed = motorSpeedMin;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setDirectionAxis() {
|
void StepperControlAxis::setDirectionAxis()
|
||||||
|
{
|
||||||
|
|
||||||
if (((!coordHomeAxis && coordCurrentPoint < coordDestinationPoint) || (coordHomeAxis && motorHomeIsUp)) ^ motorMotorInv) {
|
if (((!coordHomeAxis && coordCurrentPoint < coordDestinationPoint) || (coordHomeAxis && motorHomeIsUp)) ^ motorMotorInv)
|
||||||
setDirectionUp();
|
{
|
||||||
} else {
|
setDirectionUp();
|
||||||
setDirectionDown();
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
setDirectionDown();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::checkMovement() {
|
void StepperControlAxis::checkMovement()
|
||||||
|
{
|
||||||
|
|
||||||
checkAxisDirection();
|
checkAxisDirection();
|
||||||
|
|
||||||
// Handle movement if destination is not already reached or surpassed
|
// Handle movement if destination is not already reached or surpassed
|
||||||
if (
|
if (
|
||||||
(
|
(
|
||||||
(coordDestinationPoint > coordSourcePoint && coordCurrentPoint < coordDestinationPoint) ||
|
(coordDestinationPoint > coordSourcePoint && coordCurrentPoint < coordDestinationPoint) ||
|
||||||
(coordDestinationPoint < coordSourcePoint && coordCurrentPoint > coordDestinationPoint) ||
|
(coordDestinationPoint < coordSourcePoint && coordCurrentPoint > coordDestinationPoint) ||
|
||||||
coordHomeAxis
|
coordHomeAxis) &&
|
||||||
)
|
axisActive)
|
||||||
&& 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 end stop reached or the encoder doesn't move anymore, stop moving motor, otherwise set the timing for the next step
|
||||||
if ((coordHomeAxis && !endStopAxisReached(false)) || (!coordHomeAxis && !endStopAxisReached(!movementToHome))) {
|
if ((coordHomeAxis && !endStopAxisReached(false)) || (!coordHomeAxis && !endStopAxisReached(!movementToHome)))
|
||||||
|
{
|
||||||
|
|
||||||
// Get the axis speed, in steps per second
|
// Get the axis speed, in steps per second
|
||||||
axisSpeed = calculateSpeed( coordSourcePoint, coordCurrentPoint, coordDestinationPoint,
|
axisSpeed = calculateSpeed(coordSourcePoint, coordCurrentPoint, coordDestinationPoint,
|
||||||
motorSpeedMin, motorSpeedMax, motorStepsAcc);
|
motorSpeedMin, motorSpeedMax, motorStepsAcc);
|
||||||
|
|
||||||
// Set the moments when the step is set to true and false
|
// Set the moments when the step is set to true and false
|
||||||
if (axisSpeed > 0)
|
if (axisSpeed > 0)
|
||||||
{
|
{
|
||||||
|
|
||||||
// Take the requested speed (steps / second) and divide by the interrupt speed (interrupts per seconde)
|
// 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
|
// 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);
|
stepOnTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed / 2);
|
||||||
stepOffTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed );
|
stepOffTick = moveTicks + (1000.0 * 1000.0 / motorInterruptSpeed / axisSpeed);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
axisActive = false;
|
{
|
||||||
}
|
axisActive = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
// Destination or home reached. Deactivate the axis.
|
||||||
|
axisActive = false;
|
||||||
|
}
|
||||||
|
|
||||||
} else {
|
// If end stop for home is active, set the position to zero
|
||||||
// Destination or home reached. Deactivate the axis.
|
if (endStopAxisReached(false))
|
||||||
axisActive = 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
|
// Negative flank for the steps
|
||||||
resetMotorStep();
|
resetMotorStep();
|
||||||
checkMovement();
|
checkMovement();
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
|
{
|
||||||
|
|
||||||
if (moveTicks == stepOnTick) {
|
if (moveTicks == stepOnTick)
|
||||||
|
{
|
||||||
|
|
||||||
// Positive flank for the steps
|
// Positive flank for the steps
|
||||||
setStepAxis();
|
setStepAxis();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setStepAxis() {
|
void StepperControlAxis::setStepAxis()
|
||||||
|
{
|
||||||
|
|
||||||
if (movementUp) {
|
if (movementUp)
|
||||||
coordCurrentPoint++;
|
{
|
||||||
} else {
|
coordCurrentPoint++;
|
||||||
coordCurrentPoint--;
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
coordCurrentPoint--;
|
||||||
|
}
|
||||||
|
|
||||||
// set a step on the motors
|
// set a step on the motors
|
||||||
setMotorStep();
|
setMotorStep();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::endStopAxisReached(bool movement_forward) {
|
bool StepperControlAxis::endStopAxisReached(bool movement_forward)
|
||||||
|
{
|
||||||
|
|
||||||
bool min_endstop = false;
|
bool min_endstop = false;
|
||||||
bool max_endstop = false;
|
bool max_endstop = false;
|
||||||
bool invert = false;
|
bool invert = false;
|
||||||
|
|
||||||
if (motorEndStopInv) {
|
if (motorEndStopInv)
|
||||||
invert = true;
|
{
|
||||||
}
|
invert = true;
|
||||||
|
}
|
||||||
|
|
||||||
// for the axis to check, retrieve the end stop status
|
// for the axis to check, retrieve the end stop status
|
||||||
|
|
||||||
if (!invert) {
|
if (!invert)
|
||||||
min_endstop = endStopMin();
|
{
|
||||||
max_endstop = endStopMax();
|
min_endstop = endStopMin();
|
||||||
} else {
|
max_endstop = endStopMax();
|
||||||
min_endstop = endStopMax();
|
}
|
||||||
max_endstop = endStopMin();
|
else
|
||||||
}
|
{
|
||||||
|
min_endstop = endStopMax();
|
||||||
|
max_endstop = endStopMin();
|
||||||
|
}
|
||||||
|
|
||||||
// if moving forward, only check the end stop max
|
// if moving forward, only check the end stop max
|
||||||
// for moving backwards, check only the end stop min
|
// for moving backwards, check only the end stop min
|
||||||
|
|
||||||
if((!movement_forward && min_endstop) || (movement_forward && max_endstop)) {
|
if ((!movement_forward && min_endstop) || (movement_forward && max_endstop))
|
||||||
return 1;
|
{
|
||||||
}
|
return 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) {
|
void StepperControlAxis::StepperControlAxis::loadPinNumbers(int step, int dir, int enable, int min, int max, int step2, int dir2, int enable2)
|
||||||
pinStep = step;
|
{
|
||||||
pinDirection = dir;
|
pinStep = step;
|
||||||
pinEnable = enable;
|
pinDirection = dir;
|
||||||
|
pinEnable = enable;
|
||||||
|
|
||||||
pin2Step = step2;
|
pin2Step = step2;
|
||||||
pin2Direction = dir2;
|
pin2Direction = dir2;
|
||||||
pin2Enable = enable2;
|
pin2Enable = enable2;
|
||||||
|
|
||||||
pinMin = min;
|
pinMin = min;
|
||||||
pinMax = max;
|
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(
|
motorSpeedMax = speedMax;
|
||||||
long speedMax, long speedMin, long stepsAcc, long timeOut, bool homeIsUp, bool motorInv,
|
motorSpeedMin = speedMin;
|
||||||
bool endStInv, long interruptSpeed, bool motor2Enbl,bool motor2Inv, bool endStEnbl) {
|
motorStepsAcc = stepsAcc;
|
||||||
|
motorTimeOut = timeOut;
|
||||||
motorSpeedMax = speedMax;
|
motorHomeIsUp = homeIsUp;
|
||||||
motorSpeedMin = speedMin;
|
motorMotorInv = motorInv;
|
||||||
motorStepsAcc = stepsAcc;
|
motorEndStopInv = endStInv;
|
||||||
motorTimeOut = timeOut;
|
motorEndStopEnbl = endStEnbl;
|
||||||
motorHomeIsUp = homeIsUp;
|
motorInterruptSpeed = interruptSpeed;
|
||||||
motorMotorInv = motorInv;
|
motorMotor2Enl = motor2Enbl;
|
||||||
motorEndStopInv = endStInv;
|
motorMotor2Inv = motor2Inv;
|
||||||
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;
|
coordSourcePoint = sourcePoint;
|
||||||
coordCurrentPoint = sourcePoint;
|
coordCurrentPoint = sourcePoint;
|
||||||
coordDestinationPoint = destinationPoint;
|
coordDestinationPoint = destinationPoint;
|
||||||
coordHomeAxis = home;
|
coordHomeAxis = home;
|
||||||
|
|
||||||
// Limit normal movmement to the home position
|
// Limit normal movmement to the home position
|
||||||
if (!motorHomeIsUp && coordDestinationPoint < 0) {
|
if (!motorHomeIsUp && coordDestinationPoint < 0)
|
||||||
coordDestinationPoint = 0;
|
{
|
||||||
}
|
coordDestinationPoint = 0;
|
||||||
|
}
|
||||||
|
|
||||||
if ( motorHomeIsUp && coordDestinationPoint > 0) {
|
if (motorHomeIsUp && coordDestinationPoint > 0)
|
||||||
coordDestinationPoint = 0;
|
{
|
||||||
}
|
coordDestinationPoint = 0;
|
||||||
|
}
|
||||||
|
|
||||||
// Initialize movement variables
|
// Initialize movement variables
|
||||||
moveTicks = 0;
|
moveTicks = 0;
|
||||||
axisActive = true;
|
axisActive = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::enableMotor() {
|
void StepperControlAxis::enableMotor()
|
||||||
digitalWrite(pinEnable, LOW);
|
{
|
||||||
if (motorMotor2Enl) {
|
digitalWrite(pinEnable, LOW);
|
||||||
digitalWrite(pin2Enable, LOW);
|
if (motorMotor2Enl)
|
||||||
}
|
{
|
||||||
movementMotorActive = true;
|
digitalWrite(pin2Enable, LOW);
|
||||||
|
}
|
||||||
|
movementMotorActive = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::disableMotor() {
|
void StepperControlAxis::disableMotor()
|
||||||
digitalWrite(pinEnable, HIGH);
|
{
|
||||||
if (motorMotor2Enl) {
|
digitalWrite(pinEnable, HIGH);
|
||||||
digitalWrite(pin2Enable, HIGH);
|
if (motorMotor2Enl)
|
||||||
}
|
{
|
||||||
movementMotorActive = false;
|
digitalWrite(pin2Enable, HIGH);
|
||||||
|
}
|
||||||
|
movementMotorActive = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setDirectionUp() {
|
void StepperControlAxis::setDirectionUp()
|
||||||
if (motorMotorInv) {
|
{
|
||||||
digitalWrite(pinDirection, LOW);
|
if (motorMotorInv)
|
||||||
} else {
|
{
|
||||||
digitalWrite(pinDirection, HIGH);
|
digitalWrite(pinDirection, LOW);
|
||||||
}
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
digitalWrite(pinDirection, HIGH);
|
||||||
|
}
|
||||||
|
|
||||||
if (motorMotor2Enl && motorMotor2Inv) {
|
if (motorMotor2Enl && motorMotor2Inv)
|
||||||
digitalWrite(pin2Direction, LOW);
|
{
|
||||||
} else {
|
digitalWrite(pin2Direction, LOW);
|
||||||
digitalWrite(pin2Direction, HIGH);
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
digitalWrite(pin2Direction, HIGH);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setDirectionDown() {
|
void StepperControlAxis::setDirectionDown()
|
||||||
if (motorMotorInv) {
|
{
|
||||||
digitalWrite(pinDirection, HIGH);
|
if (motorMotorInv)
|
||||||
} else {
|
{
|
||||||
digitalWrite(pinDirection, LOW);
|
digitalWrite(pinDirection, HIGH);
|
||||||
}
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
digitalWrite(pinDirection, LOW);
|
||||||
|
}
|
||||||
|
|
||||||
if (motorMotor2Enl && motorMotor2Inv) {
|
if (motorMotor2Enl && motorMotor2Inv)
|
||||||
digitalWrite(pin2Direction, HIGH);
|
{
|
||||||
} else {
|
digitalWrite(pin2Direction, HIGH);
|
||||||
digitalWrite(pin2Direction, LOW);
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
digitalWrite(pin2Direction, LOW);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setMovementUp() {
|
void StepperControlAxis::setMovementUp()
|
||||||
movementUp = true;
|
{
|
||||||
|
movementUp = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setMovementDown() {
|
void StepperControlAxis::setMovementDown()
|
||||||
movementUp = false;
|
{
|
||||||
|
movementUp = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setDirectionHome() {
|
void StepperControlAxis::setDirectionHome()
|
||||||
if (motorHomeIsUp) {
|
{
|
||||||
setDirectionUp();
|
if (motorHomeIsUp)
|
||||||
setMovementUp();
|
{
|
||||||
} else {
|
setDirectionUp();
|
||||||
setDirectionDown();
|
setMovementUp();
|
||||||
setMovementDown();
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
setDirectionDown();
|
||||||
|
setMovementDown();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setDirectionAway() {
|
void StepperControlAxis::setDirectionAway()
|
||||||
if (motorHomeIsUp) {
|
{
|
||||||
setDirectionDown();
|
if (motorHomeIsUp)
|
||||||
setMovementDown();
|
{
|
||||||
} else {
|
setDirectionDown();
|
||||||
setDirectionUp();
|
setMovementDown();
|
||||||
setMovementUp();
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
setDirectionUp();
|
||||||
|
setMovementUp();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned long StepperControlAxis::getLength(long l1, long l2) {
|
unsigned long StepperControlAxis::getLength(long l1, long l2)
|
||||||
if (l1 > l2) {
|
{
|
||||||
return l1 - l2;
|
if (l1 > l2)
|
||||||
} else {
|
{
|
||||||
return l2 - l1;
|
return l1 - l2;
|
||||||
}
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
return l2 - l1;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::endStopsReached() {
|
bool StepperControlAxis::endStopsReached()
|
||||||
return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv)) && motorEndStopEnbl;
|
{
|
||||||
|
return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv)) && motorEndStopEnbl;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::endStopMin() {
|
bool StepperControlAxis::endStopMin()
|
||||||
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
|
{
|
||||||
return digitalRead(pinMin) && motorEndStopEnbl;
|
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
|
||||||
|
return digitalRead(pinMin) && motorEndStopEnbl;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::endStopMax() {
|
bool StepperControlAxis::endStopMax()
|
||||||
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
|
{
|
||||||
return digitalRead(pinMax) && motorEndStopEnbl;
|
//return ((digitalRead(pinMin) == motorEndStopInv) || (digitalRead(pinMax) == motorEndStopInv));
|
||||||
|
return digitalRead(pinMax) && motorEndStopEnbl;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::isAxisActive() {
|
bool StepperControlAxis::isAxisActive()
|
||||||
return axisActive;
|
{
|
||||||
|
return axisActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::deactivateAxis() {
|
void StepperControlAxis::deactivateAxis()
|
||||||
axisActive = false;
|
{
|
||||||
|
axisActive = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setMotorStep() {
|
void StepperControlAxis::setMotorStep()
|
||||||
digitalWrite(pinStep, HIGH);
|
{
|
||||||
if (pin2Enable) {
|
digitalWrite(pinStep, HIGH);
|
||||||
digitalWrite(pin2Step, HIGH);
|
if (pin2Enable)
|
||||||
}
|
{
|
||||||
|
digitalWrite(pin2Step, HIGH);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::resetMotorStep() {
|
void StepperControlAxis::resetMotorStep()
|
||||||
movementStepDone = true;
|
{
|
||||||
digitalWrite(pinStep, LOW);
|
movementStepDone = true;
|
||||||
if (pin2Enable) {
|
digitalWrite(pinStep, LOW);
|
||||||
digitalWrite(pin2Step, LOW);
|
if (pin2Enable)
|
||||||
}
|
{
|
||||||
|
digitalWrite(pin2Step, LOW);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::pointReached(long currentPoint, long destinationPoint) {
|
bool StepperControlAxis::pointReached(long currentPoint, long destinationPoint)
|
||||||
return (destinationPoint == currentPoint);
|
{
|
||||||
|
return (destinationPoint == currentPoint);
|
||||||
}
|
}
|
||||||
|
|
||||||
long StepperControlAxis::currentPosition() {
|
long StepperControlAxis::currentPosition()
|
||||||
return coordCurrentPoint;
|
{
|
||||||
|
return coordCurrentPoint;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setCurrentPosition(long newPos) {
|
void StepperControlAxis::setCurrentPosition(long newPos)
|
||||||
coordCurrentPoint = newPos;
|
{
|
||||||
|
coordCurrentPoint = newPos;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::setMaxSpeed(long speed) {
|
void StepperControlAxis::setMaxSpeed(long speed)
|
||||||
motorSpeedMax = speed;
|
{
|
||||||
|
motorSpeedMax = speed;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::activateDebugPrint() {
|
void StepperControlAxis::activateDebugPrint()
|
||||||
debugPrint = true;
|
{
|
||||||
|
debugPrint = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::isStepDone() {
|
bool StepperControlAxis::isStepDone()
|
||||||
return movementStepDone;
|
{
|
||||||
|
return movementStepDone;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlAxis::resetStepDone() {
|
void StepperControlAxis::resetStepDone()
|
||||||
movementStepDone = false;
|
{
|
||||||
|
movementStepDone = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::movingToHome() {
|
bool StepperControlAxis::movingToHome()
|
||||||
return movementToHome;
|
{
|
||||||
|
return movementToHome;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::movingUp() {
|
bool StepperControlAxis::movingUp()
|
||||||
return movementUp;
|
{
|
||||||
|
return movementUp;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::isAccelerating() {
|
bool StepperControlAxis::isAccelerating()
|
||||||
return movementAccelerating;
|
{
|
||||||
|
return movementAccelerating;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::isDecelerating() {
|
bool StepperControlAxis::isDecelerating()
|
||||||
return movementDecelerating;
|
{
|
||||||
|
return movementDecelerating;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::isCruising() {
|
bool StepperControlAxis::isCruising()
|
||||||
return movementCruising;
|
{
|
||||||
|
return movementCruising;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::isCrawling() {
|
bool StepperControlAxis::isCrawling()
|
||||||
return movementCrawling;
|
{
|
||||||
|
return movementCrawling;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool StepperControlAxis::isMotorActive() {
|
bool StepperControlAxis::isMotorActive()
|
||||||
return movementMotorActive;
|
{
|
||||||
|
return movementMotorActive;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -17,130 +17,127 @@
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
class StepperControlAxis {
|
class StepperControlAxis
|
||||||
|
{
|
||||||
|
|
||||||
public:
|
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 enableMotor();
|
||||||
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 disableMotor();
|
||||||
void loadCoordinates(long sourcePoint, long destinationPoint, bool home);
|
void checkMovement();
|
||||||
void setMaxSpeed(long speed);
|
void checkTiming();
|
||||||
|
|
||||||
void enableMotor();
|
bool isAxisActive();
|
||||||
void disableMotor();
|
void deactivateAxis();
|
||||||
void checkMovement();
|
bool isAccelerating();
|
||||||
void checkTiming();
|
bool isDecelerating();
|
||||||
|
bool isCruising();
|
||||||
|
bool isCrawling();
|
||||||
|
bool isMotorActive();
|
||||||
|
bool isMoving();
|
||||||
|
|
||||||
bool isAxisActive();
|
bool endStopMin();
|
||||||
void deactivateAxis();
|
bool endStopMax();
|
||||||
bool isAccelerating();
|
bool endStopsReached();
|
||||||
bool isDecelerating();
|
bool endStopAxisReached(bool movement_forward);
|
||||||
bool isCruising();
|
|
||||||
bool isCrawling();
|
|
||||||
bool isMotorActive();
|
|
||||||
bool isMoving();
|
|
||||||
|
|
||||||
bool endStopMin();
|
long currentPosition();
|
||||||
bool endStopMax();
|
void setCurrentPosition(long newPos);
|
||||||
bool endStopsReached();
|
|
||||||
bool endStopAxisReached(bool movement_forward);
|
|
||||||
|
|
||||||
long currentPosition();
|
void setStepAxis();
|
||||||
void setCurrentPosition(long newPos);
|
void setMotorStep();
|
||||||
|
void resetMotorStep();
|
||||||
|
|
||||||
void setStepAxis();
|
void setDirectionUp();
|
||||||
void setMotorStep();
|
void setDirectionDown();
|
||||||
void resetMotorStep();
|
void setDirectionHome();
|
||||||
|
void setDirectionAway();
|
||||||
|
void setDirectionAxis();
|
||||||
|
|
||||||
void setDirectionUp();
|
void setMovementUp();
|
||||||
void setDirectionDown();
|
void setMovementDown();
|
||||||
void setDirectionHome();
|
|
||||||
void setDirectionAway();
|
|
||||||
void setDirectionAxis();
|
|
||||||
|
|
||||||
void setMovementUp();
|
bool movingToHome();
|
||||||
void setMovementDown();
|
bool movingUp();
|
||||||
|
|
||||||
bool movingToHome();
|
bool isStepDone();
|
||||||
bool movingUp();
|
void resetStepDone();
|
||||||
|
|
||||||
bool isStepDone();
|
void activateDebugPrint();
|
||||||
void resetStepDone();
|
void test();
|
||||||
|
|
||||||
void activateDebugPrint();
|
char label;
|
||||||
void test();
|
bool movementStarted;
|
||||||
|
|
||||||
char label;
|
|
||||||
bool movementStarted;
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
int lastCalcLog = 0;
|
||||||
|
bool debugPrint = false;
|
||||||
|
|
||||||
int lastCalcLog = 0;
|
// pin settings primary motor
|
||||||
bool debugPrint = false;
|
int pinStep;
|
||||||
|
int pinDirection;
|
||||||
|
int pinEnable;
|
||||||
|
|
||||||
// pin settings primary motor
|
// pin settings primary motor
|
||||||
int pinStep;
|
int pin2Step;
|
||||||
int pinDirection;
|
int pin2Direction;
|
||||||
int pinEnable;
|
int pin2Enable;
|
||||||
|
|
||||||
// pin settings primary motor
|
// pin settings primary motor
|
||||||
int pin2Step;
|
int pinMin;
|
||||||
int pin2Direction;
|
int pinMax;
|
||||||
int pin2Enable;
|
|
||||||
|
|
||||||
// pin settings primary motor
|
// motor settings
|
||||||
int pinMin;
|
bool motorEndStopInv; // invert input (true/false) of end stops
|
||||||
int pinMax;
|
bool motorEndStopEnbl; // enable the use of the end stops
|
||||||
|
|
||||||
// motor settings
|
// motor settings
|
||||||
bool motorEndStopInv; // invert input (true/false) of end stops
|
long motorSpeedMax; // maximum speed in steps per second
|
||||||
bool motorEndStopEnbl; // enable the use of the end stops
|
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
|
// coordinates
|
||||||
long motorSpeedMax; // maximum speed in steps per second
|
long coordSourcePoint; // all coordinated in steps
|
||||||
long motorSpeedMin; // minimum speed in steps per second
|
long coordCurrentPoint;
|
||||||
long motorStepsAcc; // number of steps used for acceleration
|
long coordDestinationPoint;
|
||||||
long motorTimeOut; // timeout in seconds
|
bool coordHomeAxis; // homing command
|
||||||
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
|
// movement handling
|
||||||
long coordSourcePoint; // all coordinated in steps
|
unsigned long movementLength;
|
||||||
long coordCurrentPoint;
|
unsigned long maxLenth;
|
||||||
long coordDestinationPoint;
|
unsigned long moveTicks;
|
||||||
bool coordHomeAxis; // homing command
|
unsigned long stepOnTick;
|
||||||
|
unsigned long stepOffTick;
|
||||||
|
unsigned long axisSpeed;
|
||||||
|
|
||||||
// movement handling
|
bool axisActive;
|
||||||
unsigned long movementLength;
|
bool movementUp;
|
||||||
unsigned long maxLenth;
|
bool movementToHome;
|
||||||
unsigned long moveTicks;
|
bool movementStepDone;
|
||||||
unsigned long stepOnTick;
|
bool movementAccelerating;
|
||||||
unsigned long stepOffTick;
|
bool movementDecelerating;
|
||||||
unsigned long axisSpeed;
|
bool movementCruising;
|
||||||
|
bool movementCrawling;
|
||||||
bool axisActive;
|
bool movementMotorActive;
|
||||||
bool movementUp;
|
bool movementMoving;
|
||||||
bool movementToHome;
|
|
||||||
bool movementStepDone;
|
|
||||||
bool movementAccelerating;
|
|
||||||
bool movementDecelerating;
|
|
||||||
bool movementCruising;
|
|
||||||
bool movementCrawling;
|
|
||||||
bool movementMotorActive;
|
|
||||||
bool movementMoving;
|
|
||||||
|
|
||||||
void step(long ¤tPoint, 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();
|
|
||||||
|
|
||||||
|
void step(long ¤tPoint, 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_ */
|
#endif /* STEPPERCONTROLAXIS_H_ */
|
||||||
|
|
||||||
|
|
|
@ -1,28 +1,30 @@
|
||||||
#include "StepperControlEncoder.h"
|
#include "StepperControlEncoder.h"
|
||||||
|
|
||||||
StepperControlEncoder::StepperControlEncoder() {
|
StepperControlEncoder::StepperControlEncoder()
|
||||||
//lastCalcLog = 0;
|
{
|
||||||
|
//lastCalcLog = 0;
|
||||||
|
|
||||||
pinChannelA = 0;
|
pinChannelA = 0;
|
||||||
pinChannelB = 0;
|
pinChannelB = 0;
|
||||||
|
|
||||||
position = 0;
|
position = 0;
|
||||||
encoderType = 0; // default type
|
encoderType = 0; // default type
|
||||||
scalingFactor = 100;
|
scalingFactor = 100;
|
||||||
|
|
||||||
curValChannelA = false;
|
curValChannelA = false;
|
||||||
curValChannelA = false;
|
curValChannelA = false;
|
||||||
prvValChannelA = false;
|
prvValChannelA = false;
|
||||||
prvValChannelA = false;
|
prvValChannelA = false;
|
||||||
|
|
||||||
readChannelA = false;
|
readChannelA = false;
|
||||||
readChannelAQ = false;
|
readChannelAQ = false;
|
||||||
readChannelB = false;
|
readChannelB = false;
|
||||||
readChannelBQ = false;
|
readChannelBQ = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlEncoder::test() {
|
void StepperControlEncoder::test()
|
||||||
/*
|
{
|
||||||
|
/*
|
||||||
Serial.print("R88 ");
|
Serial.print("R88 ");
|
||||||
Serial.print("position ");
|
Serial.print("position ");
|
||||||
Serial.print(position);
|
Serial.print(position);
|
||||||
|
@ -38,34 +40,41 @@ void StepperControlEncoder::test() {
|
||||||
*/
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ) {
|
void StepperControlEncoder::loadPinNumbers(int channelA, int channelB, int channelAQ, int channelBQ)
|
||||||
pinChannelA = channelA;
|
{
|
||||||
pinChannelB = channelB;
|
pinChannelA = channelA;
|
||||||
pinChannelAQ = channelAQ;
|
pinChannelB = channelB;
|
||||||
pinChannelBQ = channelBQ;
|
pinChannelAQ = channelAQ;
|
||||||
|
pinChannelBQ = channelBQ;
|
||||||
|
|
||||||
readChannels();
|
readChannels();
|
||||||
shiftChannels();
|
shiftChannels();
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlEncoder::loadSettings(int encType, int scaling) {
|
void StepperControlEncoder::loadSettings(int encType, int scaling)
|
||||||
encoderType = encType;
|
{
|
||||||
scalingFactor = scaling;
|
encoderType = encType;
|
||||||
|
scalingFactor = scaling;
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlEncoder::setPosition(long newPosition) {
|
void StepperControlEncoder::setPosition(long newPosition)
|
||||||
position = 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) {
|
if (scalingFactor == 100 || scalingFactor <= 0)
|
||||||
return position;
|
{
|
||||||
} else {
|
return position;
|
||||||
return position * scalingFactor / 100;
|
}
|
||||||
}
|
else
|
||||||
|
{
|
||||||
|
return position * scalingFactor / 100;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Check the encoder channels for movement accoridng to thisspecification
|
/* 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
|
int delta = 0;
|
||||||
shiftChannels();
|
|
||||||
readChannels();
|
|
||||||
|
|
||||||
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
|
if (prvValChannelA == false && curValChannelA == false && prvValChannelB == false && curValChannelB == true)
|
||||||
// no fancy code, just a few simple compares. sorry
|
{
|
||||||
if (prvValChannelA == true && curValChannelA == true && prvValChannelB == false && curValChannelB == true ) {delta++;}
|
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 == true && curValChannelB == true)
|
||||||
if (prvValChannelA == false && curValChannelA == true && prvValChannelB == false && curValChannelB == false) {delta++;}
|
{
|
||||||
|
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)
|
||||||
if (prvValChannelA == true && curValChannelA == true && prvValChannelB == true && curValChannelB == false) {delta--;}
|
{
|
||||||
if (prvValChannelA == true && curValChannelA == false && prvValChannelB == false && curValChannelB == false) {delta--;}
|
delta--;
|
||||||
|
}
|
||||||
position += 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);
|
readChannelA = digitalRead(pinChannelA);
|
||||||
readChannelAQ = digitalRead(pinChannelAQ);
|
readChannelAQ = digitalRead(pinChannelAQ);
|
||||||
readChannelB = digitalRead(pinChannelB);
|
readChannelB = digitalRead(pinChannelB);
|
||||||
readChannelBQ = digitalRead(pinChannelBQ);
|
readChannelBQ = digitalRead(pinChannelBQ);
|
||||||
|
|
||||||
if (encoderType == 1) {
|
if (encoderType == 1)
|
||||||
|
{
|
||||||
|
|
||||||
// differential encoder
|
// differential encoder
|
||||||
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ)) {
|
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ))
|
||||||
curValChannelA = readChannelA;
|
{
|
||||||
curValChannelB = readChannelB;
|
curValChannelA = readChannelA;
|
||||||
}
|
curValChannelB = readChannelB;
|
||||||
}
|
}
|
||||||
else {
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
|
||||||
// encoderType <= 0
|
// encoderType <= 0
|
||||||
// non-differential incremental encoder
|
// non-differential incremental encoder
|
||||||
curValChannelA = readChannelA;
|
curValChannelA = readChannelA;
|
||||||
curValChannelB = readChannelB;
|
curValChannelB = readChannelB;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//curValChannelA = readChannelA;
|
||||||
|
//curValChannelB = readChannelB;
|
||||||
|
|
||||||
//curValChannelA = readChannelA;
|
// curValChannelA = digitalRead(pinChannelA);
|
||||||
//curValChannelB = readChannelB;
|
// 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;
|
prvValChannelA = curValChannelA;
|
||||||
prvValChannelB = curValChannelB;
|
prvValChannelB = curValChannelB;
|
||||||
}
|
}
|
||||||
|
|
|
@ -16,48 +16,45 @@
|
||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
|
|
||||||
class StepperControlEncoder {
|
class StepperControlEncoder
|
||||||
|
{
|
||||||
|
|
||||||
public:
|
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 setPosition(long newPosition);
|
||||||
void loadSettings(int encType, int scaling);
|
long currentPosition();
|
||||||
|
|
||||||
void setPosition(long newPosition);
|
void readEncoder();
|
||||||
long currentPosition();
|
void readChannels();
|
||||||
|
void shiftChannels();
|
||||||
void readEncoder();
|
void test();
|
||||||
void readChannels();
|
|
||||||
void shiftChannels();
|
|
||||||
void test();
|
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
// pin settings
|
||||||
|
int pinChannelA;
|
||||||
|
int pinChannelAQ;
|
||||||
|
int pinChannelB;
|
||||||
|
int pinChannelBQ;
|
||||||
|
|
||||||
// pin settings
|
// channels
|
||||||
int pinChannelA;
|
bool prvValChannelA;
|
||||||
int pinChannelAQ;
|
bool prvValChannelB;
|
||||||
int pinChannelB;
|
bool curValChannelA;
|
||||||
int pinChannelBQ;
|
bool curValChannelB;
|
||||||
|
|
||||||
// channels
|
bool readChannelA;
|
||||||
bool prvValChannelA;
|
bool readChannelAQ;
|
||||||
bool prvValChannelB;
|
bool readChannelB;
|
||||||
bool curValChannelA;
|
bool readChannelBQ;
|
||||||
bool curValChannelB;
|
|
||||||
|
|
||||||
bool readChannelA;
|
|
||||||
bool readChannelAQ;
|
|
||||||
bool readChannelB;
|
|
||||||
bool readChannelBQ;
|
|
||||||
|
|
||||||
// encoder
|
|
||||||
long position;
|
|
||||||
int scalingFactor;
|
|
||||||
int encoderType;
|
|
||||||
|
|
||||||
|
// encoder
|
||||||
|
long position;
|
||||||
|
int scalingFactor;
|
||||||
|
int encoderType;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* STEPPERCONTROLENCODER_H_ */
|
#endif /* STEPPERCONTROLENCODER_H_ */
|
||||||
|
|
||||||
|
|
|
@ -8,15 +8,15 @@
|
||||||
* Modified again, June 2014 by Paul Stoffregen
|
* Modified again, June 2014 by Paul Stoffregen
|
||||||
*
|
*
|
||||||
* This is free software. You can redistribute it and/or modify it under
|
* This is free software. You can redistribute it and/or modify it under
|
||||||
* the terms of Creative Commons Attribution 3.0 United States License.
|
* 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/
|
* 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.
|
* or send a letter to Creative Commons, 171 Second Street, Suite 300, San Francisco, California, 94105, USA.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "TimerOne.h"
|
#include "TimerOne.h"
|
||||||
|
|
||||||
TimerOne Timer1; // preinstatiate
|
TimerOne Timer1; // preinstatiate
|
||||||
|
|
||||||
unsigned short TimerOne::pwmPeriod = 0;
|
unsigned short TimerOne::pwmPeriod = 0;
|
||||||
unsigned char TimerOne::clockSelectBits = 0;
|
unsigned char TimerOne::clockSelectBits = 0;
|
||||||
|
@ -33,11 +33,13 @@ ISR(TIMER1_OVF_vect)
|
||||||
void ftm1_isr(void)
|
void ftm1_isr(void)
|
||||||
{
|
{
|
||||||
uint32_t sc = FTM1_SC;
|
uint32_t sc = FTM1_SC;
|
||||||
#ifdef KINETISL
|
#ifdef KINETISL
|
||||||
if (sc & 0x80) FTM1_SC = sc;
|
if (sc & 0x80)
|
||||||
#else
|
FTM1_SC = sc;
|
||||||
if (sc & 0x80) FTM1_SC = sc & 0x7F;
|
#else
|
||||||
#endif
|
if (sc & 0x80)
|
||||||
|
FTM1_SC = sc & 0x7F;
|
||||||
|
#endif
|
||||||
Timer1.isrCallback();
|
Timer1.isrCallback();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
533
src/TimerOne.h
533
src/TimerOne.h
|
@ -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 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 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
|
* 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
|
* This is free software. You can redistribute it and/or modify it under
|
||||||
* the terms of Creative Commons Attribution 3.0 United States License.
|
* 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/
|
* 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.
|
* 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"
|
#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
|
// 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
|
// inlined by the compiler. In the very common case with constant values
|
||||||
// the compiler will perform all calculations and simply write constants
|
// the compiler will perform all calculations and simply write constants
|
||||||
// to the hardware registers (for example, setPeriod).
|
// to the hardware registers (for example, setPeriod).
|
||||||
|
|
||||||
|
|
||||||
class TimerOne
|
class TimerOne
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
#if defined(__AVR__)
|
#if defined(__AVR__)
|
||||||
public:
|
public:
|
||||||
//****************************
|
//****************************
|
||||||
// Configuration
|
// Configuration
|
||||||
//****************************
|
//****************************
|
||||||
void initialize(unsigned long microseconds=1000000) __attribute__((always_inline)) {
|
void initialize(unsigned long microseconds = 1000000) __attribute__((always_inline))
|
||||||
TCCR1B = _BV(WGM13); // set mode as phase and frequency correct pwm, stop the timer
|
{
|
||||||
TCCR1A = 0; // clear control register A
|
TCCR1B = _BV(WGM13); // set mode as phase and frequency correct pwm, stop the timer
|
||||||
setPeriod(microseconds);
|
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)) {
|
else if (cycles < TIMER1_RESOLUTION * 8)
|
||||||
const unsigned long cycles = (F_CPU / 2000000) * microseconds;
|
{
|
||||||
if (cycles < TIMER1_RESOLUTION) {
|
clockSelectBits = _BV(CS11);
|
||||||
clockSelectBits = _BV(CS10);
|
pwmPeriod = cycles / 8;
|
||||||
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 * 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
|
// Run Control
|
||||||
//****************************
|
//****************************
|
||||||
void start() __attribute__((always_inline)) {
|
void start() __attribute__((always_inline))
|
||||||
TCCR1B = 0;
|
{
|
||||||
TCNT1 = 0; // TODO: does this cause an undesired interrupt?
|
TCCR1B = 0;
|
||||||
resume();
|
TCNT1 = 0; // TODO: does this cause an undesired interrupt?
|
||||||
}
|
resume();
|
||||||
void stop() __attribute__((always_inline)) {
|
}
|
||||||
TCCR1B = _BV(WGM13);
|
void stop() __attribute__((always_inline))
|
||||||
}
|
{
|
||||||
void restart() __attribute__((always_inline)) {
|
TCCR1B = _BV(WGM13);
|
||||||
start();
|
}
|
||||||
}
|
void restart() __attribute__((always_inline))
|
||||||
void resume() __attribute__((always_inline)) {
|
{
|
||||||
TCCR1B = _BV(WGM13) | clockSelectBits;
|
start();
|
||||||
}
|
}
|
||||||
|
void resume() __attribute__((always_inline))
|
||||||
|
{
|
||||||
|
TCCR1B = _BV(WGM13) | clockSelectBits;
|
||||||
|
}
|
||||||
|
|
||||||
//****************************
|
//****************************
|
||||||
// PWM outputs
|
// PWM outputs
|
||||||
//****************************
|
//****************************
|
||||||
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline)) {
|
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline))
|
||||||
unsigned long dutyCycle = pwmPeriod;
|
{
|
||||||
dutyCycle *= duty;
|
unsigned long dutyCycle = pwmPeriod;
|
||||||
dutyCycle >>= 10;
|
dutyCycle *= duty;
|
||||||
if (pin == TIMER1_A_PIN) OCR1A = dutyCycle;
|
dutyCycle >>= 10;
|
||||||
#ifdef TIMER1_B_PIN
|
if (pin == TIMER1_A_PIN)
|
||||||
else if (pin == TIMER1_B_PIN) OCR1B = dutyCycle;
|
OCR1A = dutyCycle;
|
||||||
#endif
|
#ifdef TIMER1_B_PIN
|
||||||
#ifdef TIMER1_C_PIN
|
else if (pin == TIMER1_B_PIN)
|
||||||
else if (pin == TIMER1_C_PIN) OCR1C = dutyCycle;
|
OCR1B = dutyCycle;
|
||||||
#endif
|
#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)) {
|
#ifdef TIMER1_B_PIN
|
||||||
if (pin == TIMER1_A_PIN) { pinMode(TIMER1_A_PIN, OUTPUT); TCCR1A |= _BV(COM1A1); }
|
else if (pin == TIMER1_B_PIN)
|
||||||
#ifdef TIMER1_B_PIN
|
{
|
||||||
else if (pin == TIMER1_B_PIN) { pinMode(TIMER1_B_PIN, OUTPUT); TCCR1A |= _BV(COM1B1); }
|
pinMode(TIMER1_B_PIN, OUTPUT);
|
||||||
#endif
|
TCCR1A |= _BV(COM1B1);
|
||||||
#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)) {
|
#endif
|
||||||
if (microseconds > 0) setPeriod(microseconds);
|
#ifdef TIMER1_C_PIN
|
||||||
pwm(pin, duty);
|
else if (pin == TIMER1_C_PIN)
|
||||||
}
|
{
|
||||||
void disablePwm(char pin) __attribute__((always_inline)) {
|
pinMode(TIMER1_C_PIN, OUTPUT);
|
||||||
if (pin == TIMER1_A_PIN) TCCR1A &= ~_BV(COM1A1);
|
TCCR1A |= _BV(COM1C1);
|
||||||
#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
|
||||||
|
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
|
// Interrupt Function
|
||||||
//****************************
|
//****************************
|
||||||
void attachInterrupt(void (*isr)()) __attribute__((always_inline)) {
|
void attachInterrupt(void (*isr)()) __attribute__((always_inline))
|
||||||
isrCallback = isr;
|
{
|
||||||
TIMSK1 = _BV(TOIE1);
|
isrCallback = isr;
|
||||||
}
|
TIMSK1 = _BV(TOIE1);
|
||||||
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline)) {
|
}
|
||||||
if(microseconds > 0) setPeriod(microseconds);
|
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline))
|
||||||
attachInterrupt(isr);
|
{
|
||||||
}
|
if (microseconds > 0)
|
||||||
void detachInterrupt() __attribute__((always_inline)) {
|
setPeriod(microseconds);
|
||||||
TIMSK1 = 0;
|
attachInterrupt(isr);
|
||||||
}
|
}
|
||||||
static void (*isrCallback)();
|
void detachInterrupt() __attribute__((always_inline))
|
||||||
|
{
|
||||||
private:
|
TIMSK1 = 0;
|
||||||
// properties
|
}
|
||||||
static unsigned short pwmPeriod;
|
static void (*isrCallback)();
|
||||||
static unsigned char clockSelectBits;
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
// properties
|
||||||
|
static unsigned short pwmPeriod;
|
||||||
|
static unsigned char clockSelectBits;
|
||||||
|
|
||||||
#elif defined(__arm__) && defined(CORE_TEENSY)
|
#elif defined(__arm__) && defined(CORE_TEENSY)
|
||||||
|
|
||||||
#if defined(KINETISK)
|
#if defined(KINETISK)
|
||||||
#define F_TIMER F_BUS
|
#define F_TIMER F_BUS
|
||||||
#elif defined(KINETISL)
|
#elif defined(KINETISL)
|
||||||
#define F_TIMER (F_PLL/2)
|
#define F_TIMER (F_PLL / 2)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
public:
|
public:
|
||||||
//****************************
|
//****************************
|
||||||
// Configuration
|
// Configuration
|
||||||
//****************************
|
//****************************
|
||||||
void initialize(unsigned long microseconds=1000000) __attribute__((always_inline)) {
|
void initialize(unsigned long microseconds = 1000000) __attribute__((always_inline))
|
||||||
setPeriod(microseconds);
|
{
|
||||||
|
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)) {
|
else if (cycles < TIMER1_RESOLUTION * 2)
|
||||||
const unsigned long cycles = (F_TIMER / 2000000) * microseconds;
|
{
|
||||||
if (cycles < TIMER1_RESOLUTION) {
|
clockSelectBits = 1;
|
||||||
clockSelectBits = 0;
|
pwmPeriod = cycles >> 1;
|
||||||
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 * 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
|
// Run Control
|
||||||
//****************************
|
//****************************
|
||||||
void start() __attribute__((always_inline)) {
|
void start() __attribute__((always_inline))
|
||||||
stop();
|
{
|
||||||
FTM1_CNT = 0;
|
stop();
|
||||||
resume();
|
FTM1_CNT = 0;
|
||||||
}
|
resume();
|
||||||
void stop() __attribute__((always_inline)) {
|
}
|
||||||
FTM1_SC = FTM1_SC & (FTM_SC_TOIE | FTM_SC_CPWMS | FTM_SC_PS(7));
|
void stop() __attribute__((always_inline))
|
||||||
}
|
{
|
||||||
void restart() __attribute__((always_inline)) {
|
FTM1_SC = FTM1_SC & (FTM_SC_TOIE | FTM_SC_CPWMS | FTM_SC_PS(7));
|
||||||
start();
|
}
|
||||||
}
|
void restart() __attribute__((always_inline))
|
||||||
void resume() __attribute__((always_inline)) {
|
{
|
||||||
FTM1_SC = (FTM1_SC & (FTM_SC_TOIE | FTM_SC_PS(7))) | FTM_SC_CPWMS | FTM_SC_CLKS(1);
|
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
|
// PWM outputs
|
||||||
//****************************
|
//****************************
|
||||||
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline)) {
|
void setPwmDuty(char pin, unsigned int duty) __attribute__((always_inline))
|
||||||
unsigned long dutyCycle = pwmPeriod;
|
{
|
||||||
dutyCycle *= duty;
|
unsigned long dutyCycle = pwmPeriod;
|
||||||
dutyCycle >>= 10;
|
dutyCycle *= duty;
|
||||||
if (pin == TIMER1_A_PIN) {
|
dutyCycle >>= 10;
|
||||||
FTM1_C0V = dutyCycle;
|
if (pin == TIMER1_A_PIN)
|
||||||
} else if (pin == TIMER1_B_PIN) {
|
{
|
||||||
FTM1_C1V = dutyCycle;
|
FTM1_C0V = dutyCycle;
|
||||||
}
|
|
||||||
}
|
}
|
||||||
void pwm(char pin, unsigned int duty) __attribute__((always_inline)) {
|
else if (pin == TIMER1_B_PIN)
|
||||||
setPwmDuty(pin, duty);
|
{
|
||||||
if (pin == TIMER1_A_PIN) {
|
FTM1_C1V = dutyCycle;
|
||||||
*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;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
void pwm(char pin, unsigned int duty, unsigned long microseconds) __attribute__((always_inline)) {
|
}
|
||||||
if (microseconds > 0) setPeriod(microseconds);
|
void pwm(char pin, unsigned int duty) __attribute__((always_inline))
|
||||||
pwm(pin, duty);
|
{
|
||||||
|
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)) {
|
else if (pin == TIMER1_B_PIN)
|
||||||
if (pin == TIMER1_A_PIN) {
|
{
|
||||||
*portConfigRegister(TIMER1_A_PIN) = 0;
|
*portConfigRegister(TIMER1_B_PIN) = PORT_PCR_MUX(3) | PORT_PCR_DSE | PORT_PCR_SRE;
|
||||||
} else if (pin == TIMER1_B_PIN) {
|
|
||||||
*portConfigRegister(TIMER1_B_PIN) = 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
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
|
// Interrupt Function
|
||||||
//****************************
|
//****************************
|
||||||
void attachInterrupt(void (*isr)()) __attribute__((always_inline)) {
|
void attachInterrupt(void (*isr)()) __attribute__((always_inline))
|
||||||
isrCallback = isr;
|
{
|
||||||
FTM1_SC |= FTM_SC_TOIE;
|
isrCallback = isr;
|
||||||
NVIC_ENABLE_IRQ(IRQ_FTM1);
|
FTM1_SC |= FTM_SC_TOIE;
|
||||||
}
|
NVIC_ENABLE_IRQ(IRQ_FTM1);
|
||||||
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline)) {
|
}
|
||||||
if(microseconds > 0) setPeriod(microseconds);
|
void attachInterrupt(void (*isr)(), unsigned long microseconds) __attribute__((always_inline))
|
||||||
attachInterrupt(isr);
|
{
|
||||||
}
|
if (microseconds > 0)
|
||||||
void detachInterrupt() __attribute__((always_inline)) {
|
setPeriod(microseconds);
|
||||||
FTM1_SC &= ~FTM_SC_TOIE;
|
attachInterrupt(isr);
|
||||||
NVIC_DISABLE_IRQ(IRQ_FTM1);
|
}
|
||||||
}
|
void detachInterrupt() __attribute__((always_inline))
|
||||||
static void (*isrCallback)();
|
{
|
||||||
|
FTM1_SC &= ~FTM_SC_TOIE;
|
||||||
|
NVIC_DISABLE_IRQ(IRQ_FTM1);
|
||||||
|
}
|
||||||
|
static void (*isrCallback)();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// properties
|
// properties
|
||||||
static unsigned short pwmPeriod;
|
static unsigned short pwmPeriod;
|
||||||
static unsigned char clockSelectBits;
|
static unsigned char clockSelectBits;
|
||||||
|
|
||||||
#undef F_TIMER
|
#undef F_TIMER
|
||||||
|
|
||||||
|
@ -301,4 +367,3 @@ class TimerOne
|
||||||
extern TimerOne Timer1;
|
extern TimerOne Timer1;
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -8,9 +8,8 @@
|
||||||
#include "TimerOne.h"
|
#include "TimerOne.h"
|
||||||
#include "MemoryFree.h"
|
#include "MemoryFree.h"
|
||||||
|
|
||||||
|
|
||||||
static char commandEndChar = 0x0A;
|
static char commandEndChar = 0x0A;
|
||||||
static GCodeProcessor* gCodeProcessor = new GCodeProcessor();
|
static GCodeProcessor *gCodeProcessor = new GCodeProcessor();
|
||||||
|
|
||||||
unsigned long lastAction;
|
unsigned long lastAction;
|
||||||
unsigned long currentTime;
|
unsigned long currentTime;
|
||||||
|
@ -25,9 +24,10 @@ int incomingCommandPointer = 0;
|
||||||
|
|
||||||
// Blink led routine used for testing
|
// Blink led routine used for testing
|
||||||
bool blink = false;
|
bool blink = false;
|
||||||
void blinkLed() {
|
void blinkLed()
|
||||||
blink = !blink;
|
{
|
||||||
digitalWrite(LED_PIN,blink);
|
blink = !blink;
|
||||||
|
digitalWrite(LED_PIN, blink);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Interrupt handling for:
|
// Interrupt handling for:
|
||||||
|
@ -37,208 +37,218 @@ void blinkLed() {
|
||||||
//
|
//
|
||||||
bool interruptBusy = false;
|
bool interruptBusy = false;
|
||||||
int interruptSecondTimer = 0;
|
int interruptSecondTimer = 0;
|
||||||
void interrupt(void) {
|
void interrupt(void)
|
||||||
interruptSecondTimer++;
|
{
|
||||||
|
interruptSecondTimer++;
|
||||||
|
|
||||||
if (interruptBusy == false) {
|
if (interruptBusy == false)
|
||||||
|
{
|
||||||
|
|
||||||
interruptBusy = true;
|
interruptBusy = true;
|
||||||
StepperControl::getInstance()->handleMovementInterrupt();
|
StepperControl::getInstance()->handleMovementInterrupt();
|
||||||
|
|
||||||
// Check the actions triggered once per second
|
// Check the actions triggered once per second
|
||||||
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED) {
|
if (interruptSecondTimer >= 1000000 / MOVEMENT_INTERRUPT_SPEED)
|
||||||
interruptSecondTimer = 0;
|
{
|
||||||
PinGuard::getInstance()->checkPins();
|
interruptSecondTimer = 0;
|
||||||
//blinkLed();
|
PinGuard::getInstance()->checkPins();
|
||||||
}
|
//blinkLed();
|
||||||
|
}
|
||||||
|
|
||||||
interruptBusy = false;
|
interruptBusy = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
//The setup function is called once at startup of the sketch
|
//The setup function is called once at startup of the sketch
|
||||||
void setup() {
|
void setup()
|
||||||
|
{
|
||||||
|
|
||||||
// Setup pin input/output settings
|
// Setup pin input/output settings
|
||||||
pinMode(X_STEP_PIN , OUTPUT);
|
pinMode(X_STEP_PIN, OUTPUT);
|
||||||
pinMode(X_DIR_PIN , OUTPUT);
|
pinMode(X_DIR_PIN, OUTPUT);
|
||||||
pinMode(X_ENABLE_PIN, OUTPUT);
|
pinMode(X_ENABLE_PIN, OUTPUT);
|
||||||
pinMode(E_STEP_PIN , OUTPUT);
|
pinMode(E_STEP_PIN, OUTPUT);
|
||||||
pinMode(E_DIR_PIN , OUTPUT);
|
pinMode(E_DIR_PIN, OUTPUT);
|
||||||
pinMode(E_ENABLE_PIN, OUTPUT);
|
pinMode(E_ENABLE_PIN, OUTPUT);
|
||||||
pinMode(X_MIN_PIN , INPUT_PULLUP );
|
pinMode(X_MIN_PIN, INPUT_PULLUP);
|
||||||
pinMode(X_MAX_PIN , INPUT_PULLUP );
|
pinMode(X_MAX_PIN, INPUT_PULLUP);
|
||||||
|
|
||||||
pinMode(Y_STEP_PIN , OUTPUT);
|
pinMode(Y_STEP_PIN, OUTPUT);
|
||||||
pinMode(Y_DIR_PIN , OUTPUT);
|
pinMode(Y_DIR_PIN, OUTPUT);
|
||||||
pinMode(Y_ENABLE_PIN, OUTPUT);
|
pinMode(Y_ENABLE_PIN, OUTPUT);
|
||||||
pinMode(Y_MIN_PIN , INPUT_PULLUP );
|
pinMode(Y_MIN_PIN, INPUT_PULLUP);
|
||||||
pinMode(Y_MAX_PIN , INPUT_PULLUP );
|
pinMode(Y_MAX_PIN, INPUT_PULLUP);
|
||||||
|
|
||||||
pinMode(Z_STEP_PIN , OUTPUT);
|
pinMode(Z_STEP_PIN, OUTPUT);
|
||||||
pinMode(Z_DIR_PIN , OUTPUT);
|
pinMode(Z_DIR_PIN, OUTPUT);
|
||||||
pinMode(Z_ENABLE_PIN, OUTPUT);
|
pinMode(Z_ENABLE_PIN, OUTPUT);
|
||||||
pinMode(Z_MIN_PIN , INPUT_PULLUP );
|
pinMode(Z_MIN_PIN, INPUT_PULLUP);
|
||||||
pinMode(Z_MAX_PIN , INPUT_PULLUP );
|
pinMode(Z_MAX_PIN, INPUT_PULLUP);
|
||||||
|
|
||||||
pinMode(HEATER_0_PIN, OUTPUT);
|
pinMode(HEATER_0_PIN, OUTPUT);
|
||||||
pinMode(HEATER_1_PIN, OUTPUT);
|
pinMode(HEATER_1_PIN, OUTPUT);
|
||||||
pinMode(FAN_PIN , OUTPUT);
|
pinMode(FAN_PIN, OUTPUT);
|
||||||
pinMode(LED_PIN , OUTPUT);
|
pinMode(LED_PIN, OUTPUT);
|
||||||
|
|
||||||
//pinMode(SERVO_0_PIN , OUTPUT);
|
//pinMode(SERVO_0_PIN , OUTPUT);
|
||||||
//pinMode(SERVO_1_PIN , OUTPUT);
|
//pinMode(SERVO_1_PIN , OUTPUT);
|
||||||
|
|
||||||
digitalWrite(X_ENABLE_PIN, HIGH);
|
digitalWrite(X_ENABLE_PIN, HIGH);
|
||||||
digitalWrite(E_ENABLE_PIN, HIGH);
|
digitalWrite(E_ENABLE_PIN, HIGH);
|
||||||
digitalWrite(Y_ENABLE_PIN, HIGH);
|
digitalWrite(Y_ENABLE_PIN, HIGH);
|
||||||
digitalWrite(Z_ENABLE_PIN, HIGH);
|
digitalWrite(Z_ENABLE_PIN, HIGH);
|
||||||
|
|
||||||
Serial.begin(115200);
|
Serial.begin(115200);
|
||||||
|
|
||||||
delay(100);
|
delay(100);
|
||||||
|
|
||||||
// Start the motor handling
|
// Start the motor handling
|
||||||
//ServoControl::getInstance()->attach();
|
//ServoControl::getInstance()->attach();
|
||||||
|
|
||||||
// Dump all values to the serial interface
|
// Dump all values to the serial interface
|
||||||
ParameterList::getInstance()->readAllValues();
|
ParameterList::getInstance()->readAllValues();
|
||||||
|
|
||||||
// Get the settings for the pin guard
|
// Get the settings for the pin guard
|
||||||
PinGuard::getInstance()->loadConfig();
|
PinGuard::getInstance()->loadConfig();
|
||||||
|
|
||||||
// Start the interrupt used for moving
|
// Start the interrupt used for moving
|
||||||
// Interrupt management code library written by Paul Stoffregen
|
// Interrupt management code library written by Paul Stoffregen
|
||||||
// The default time 100 micro seconds
|
// The default time 100 micro seconds
|
||||||
|
|
||||||
Timer1.attachInterrupt(interrupt);
|
Timer1.attachInterrupt(interrupt);
|
||||||
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
|
Timer1.initialize(MOVEMENT_INTERRUPT_SPEED);
|
||||||
Timer1.start();
|
Timer1.start();
|
||||||
|
|
||||||
// Initialize the inactivity check
|
// Initialize the inactivity check
|
||||||
lastAction = millis();
|
lastAction = millis();
|
||||||
}
|
}
|
||||||
|
|
||||||
// The loop function is called in an endless loop
|
// 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
|
// Save current time stamp for timeout actions
|
||||||
lastAction = millis();
|
lastAction = millis();
|
||||||
|
|
||||||
// Get the input and start processing on receiving 'new line'
|
// Get the input and start processing on receiving 'new line'
|
||||||
incomingChar = Serial.read();
|
incomingChar = Serial.read();
|
||||||
incomingCommandArray[incomingCommandPointer] = incomingChar;
|
incomingCommandArray[incomingCommandPointer] = incomingChar;
|
||||||
incomingCommandPointer++;
|
incomingCommandPointer++;
|
||||||
|
|
||||||
// If the string is getting to long, cap it off with a new line and let it process anyway
|
// If the string is getting to long, cap it off with a new line and let it process anyway
|
||||||
if (incomingCommandPointer >= INCOMING_CMD_BUF_SIZE - 1) {
|
if (incomingCommandPointer >= INCOMING_CMD_BUF_SIZE - 1)
|
||||||
incomingChar = '\n';
|
{
|
||||||
incomingCommandArray[incomingCommandPointer] = incomingChar;
|
incomingChar = '\n';
|
||||||
incomingCommandPointer++;
|
incomingCommandArray[incomingCommandPointer] = incomingChar;
|
||||||
}
|
incomingCommandPointer++;
|
||||||
|
}
|
||||||
|
|
||||||
if (incomingChar == '\n' || incomingCommandPointer >= INCOMING_CMD_BUF_SIZE) {
|
if (incomingChar == '\n' || incomingCommandPointer >= INCOMING_CMD_BUF_SIZE)
|
||||||
|
{
|
||||||
|
|
||||||
//commandString += incomingChar;
|
//commandString += incomingChar;
|
||||||
//String commandString = Serial.readStringUntil(commandEndChar);
|
//String commandString = Serial.readStringUntil(commandEndChar);
|
||||||
//char commandChar[currentCommand.length()];
|
//char commandChar[currentCommand.length()];
|
||||||
//currentCommand.toCharArray(commandChar, currentCommand.length());
|
//currentCommand.toCharArray(commandChar, currentCommand.length());
|
||||||
|
|
||||||
char commandChar[incomingCommandPointer + 1];
|
char commandChar[incomingCommandPointer + 1];
|
||||||
for (int i = 0; i < incomingCommandPointer -1; i++) {
|
for (int i = 0; i < incomingCommandPointer - 1; i++)
|
||||||
commandChar[i] = incomingCommandArray[i];
|
{
|
||||||
}
|
commandChar[i] = incomingCommandArray[i];
|
||||||
commandChar[incomingCommandPointer] = 0;
|
}
|
||||||
|
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.
|
// Create a command and let it execute
|
||||||
// because there are issues with passing the
|
//Command* command = new Command(commandString);
|
||||||
// string to the command object
|
Command *command = new Command(commandChar);
|
||||||
|
|
||||||
// Create a command and let it execute
|
if (LOGGING)
|
||||||
//Command* command = new Command(commandString);
|
{
|
||||||
Command* command = new Command(commandChar);
|
command->print();
|
||||||
|
}
|
||||||
|
|
||||||
if(LOGGING) {
|
gCodeProcessor->execute(command);
|
||||||
command->print();
|
|
||||||
}
|
|
||||||
|
|
||||||
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()) {
|
Serial.print(COMM_REPORT_COMMENT);
|
||||||
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();
|
Serial.print(" loading parameters ");
|
||||||
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
|
||||||
Serial.print(COMM_REPORT_COMMENT);
|
StepperControl::getInstance()->loadSettings();
|
||||||
Serial.print(" loading parameters ");
|
PinGuard::getInstance()->loadConfig();
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
}
|
||||||
|
|
||||||
StepperControl::getInstance()->loadSettings();
|
// Do periodic checks and feedback
|
||||||
PinGuard::getInstance()->loadConfig();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
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) > 5000)
|
||||||
if (currentTime < lastAction) {
|
{
|
||||||
|
// After an idle time, send the idle message
|
||||||
|
|
||||||
// If the device timer overruns, reset the idle counter
|
Serial.print(COMM_REPORT_CMD_IDLE);
|
||||||
lastAction = millis();
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
}
|
|
||||||
else {
|
|
||||||
|
|
||||||
if ((currentTime - lastAction) > 5000) {
|
StepperControl::getInstance()->storePosition();
|
||||||
// After an idle time, send the idle message
|
CurrentState::getInstance()->printPosition();
|
||||||
|
|
||||||
Serial.print(COMM_REPORT_CMD_IDLE);
|
CurrentState::getInstance()->storeEndStops();
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
CurrentState::getInstance()->printEndStops();
|
||||||
|
|
||||||
StepperControl::getInstance()->storePosition();
|
Serial.print(COMM_REPORT_COMMENT);
|
||||||
CurrentState::getInstance()->printPosition();
|
Serial.print(" MEM ");
|
||||||
|
Serial.print(freeMemory());
|
||||||
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
|
||||||
CurrentState::getInstance()->storeEndStops();
|
Serial.print(COMM_REPORT_COMMENT);
|
||||||
CurrentState::getInstance()->printEndStops();
|
Serial.print(" Cycle ");
|
||||||
|
Serial.print(cycleCounter);
|
||||||
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
|
||||||
Serial.print(COMM_REPORT_COMMENT);
|
StepperControl::getInstance()->test();
|
||||||
Serial.print(" MEM ");
|
|
||||||
Serial.print(freeMemory());
|
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
|
||||||
|
|
||||||
Serial.print(COMM_REPORT_COMMENT);
|
//ParameterList::getInstance()->readAllValues();
|
||||||
Serial.print(" Cycle ");
|
|
||||||
Serial.print(cycleCounter);
|
|
||||||
CurrentState::getInstance()->printQAndNewLine();
|
|
||||||
|
|
||||||
StepperControl::getInstance()->test();
|
//StepperControl::getInstance()->test();
|
||||||
|
|
||||||
//ParameterList::getInstance()->readAllValues();
|
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
|
||||||
|
// Serial.print(COMM_REPORT_NO_CONFIG);
|
||||||
|
// }
|
||||||
|
|
||||||
|
cycleCounter++;
|
||||||
//StepperControl::getInstance()->test();
|
lastAction = millis();
|
||||||
|
}
|
||||||
// if (ParameterList::getInstance()->getValue(PARAM_CONFIG_OK) != 1) {
|
}
|
||||||
// Serial.print(COMM_REPORT_NO_CONFIG);
|
|
||||||
// }
|
|
||||||
|
|
||||||
cycleCounter++;
|
|
||||||
lastAction = millis();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -25,6 +25,5 @@ void setup();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//Do not add code below this line
|
//Do not add code below this line
|
||||||
#endif /* _farmbot_arduino_controller_H_ */
|
#endif /* _farmbot_arduino_controller_H_ */
|
||||||
|
|
|
@ -4,139 +4,139 @@
|
||||||
// Wiring-S
|
// Wiring-S
|
||||||
//
|
//
|
||||||
#if defined(__AVR_ATmega644P__) && defined(WIRING)
|
#if defined(__AVR_ATmega644P__) && defined(WIRING)
|
||||||
#define TIMER1_A_PIN 5
|
#define TIMER1_A_PIN 5
|
||||||
#define TIMER1_B_PIN 4
|
#define TIMER1_B_PIN 4
|
||||||
#define TIMER1_ICP_PIN 6
|
#define TIMER1_ICP_PIN 6
|
||||||
|
|
||||||
// Teensy 2.0
|
// Teensy 2.0
|
||||||
//
|
//
|
||||||
#elif defined(__AVR_ATmega32U4__) && defined(CORE_TEENSY)
|
#elif defined(__AVR_ATmega32U4__) && defined(CORE_TEENSY)
|
||||||
#define TIMER1_A_PIN 14
|
#define TIMER1_A_PIN 14
|
||||||
#define TIMER1_B_PIN 15
|
#define TIMER1_B_PIN 15
|
||||||
#define TIMER1_C_PIN 4
|
#define TIMER1_C_PIN 4
|
||||||
#define TIMER1_ICP_PIN 22
|
#define TIMER1_ICP_PIN 22
|
||||||
#define TIMER1_CLK_PIN 11
|
#define TIMER1_CLK_PIN 11
|
||||||
#define TIMER3_A_PIN 9
|
#define TIMER3_A_PIN 9
|
||||||
#define TIMER3_ICP_PIN 10
|
#define TIMER3_ICP_PIN 10
|
||||||
|
|
||||||
// Teensy++ 2.0
|
// Teensy++ 2.0
|
||||||
#elif defined(__AVR_AT90USB1286__) && defined(CORE_TEENSY)
|
#elif defined(__AVR_AT90USB1286__) && defined(CORE_TEENSY)
|
||||||
#define TIMER1_A_PIN 25
|
#define TIMER1_A_PIN 25
|
||||||
#define TIMER1_B_PIN 26
|
#define TIMER1_B_PIN 26
|
||||||
#define TIMER1_C_PIN 27
|
#define TIMER1_C_PIN 27
|
||||||
#define TIMER1_ICP_PIN 4
|
#define TIMER1_ICP_PIN 4
|
||||||
#define TIMER1_CLK_PIN 6
|
#define TIMER1_CLK_PIN 6
|
||||||
#define TIMER3_A_PIN 16
|
#define TIMER3_A_PIN 16
|
||||||
#define TIMER3_B_PIN 15
|
#define TIMER3_B_PIN 15
|
||||||
#define TIMER3_C_PIN 14
|
#define TIMER3_C_PIN 14
|
||||||
#define TIMER3_ICP_PIN 17
|
#define TIMER3_ICP_PIN 17
|
||||||
#define TIMER3_CLK_PIN 13
|
#define TIMER3_CLK_PIN 13
|
||||||
|
|
||||||
// Teensy 3.0
|
// Teensy 3.0
|
||||||
//
|
//
|
||||||
#elif defined(__MK20DX128__)
|
#elif defined(__MK20DX128__)
|
||||||
#define TIMER1_A_PIN 3
|
#define TIMER1_A_PIN 3
|
||||||
#define TIMER1_B_PIN 4
|
#define TIMER1_B_PIN 4
|
||||||
#define TIMER1_ICP_PIN 4
|
#define TIMER1_ICP_PIN 4
|
||||||
|
|
||||||
// Teensy 3.1
|
// Teensy 3.1
|
||||||
//
|
//
|
||||||
#elif defined(__MK20DX256__)
|
#elif defined(__MK20DX256__)
|
||||||
#define TIMER1_A_PIN 3
|
#define TIMER1_A_PIN 3
|
||||||
#define TIMER1_B_PIN 4
|
#define TIMER1_B_PIN 4
|
||||||
#define TIMER1_ICP_PIN 4
|
#define TIMER1_ICP_PIN 4
|
||||||
#define TIMER3_A_PIN 32
|
#define TIMER3_A_PIN 32
|
||||||
#define TIMER3_B_PIN 25
|
#define TIMER3_B_PIN 25
|
||||||
#define TIMER3_ICP_PIN 32
|
#define TIMER3_ICP_PIN 32
|
||||||
|
|
||||||
// Teensy-LC
|
// Teensy-LC
|
||||||
//
|
//
|
||||||
#elif defined(__MKL26Z64__)
|
#elif defined(__MKL26Z64__)
|
||||||
#define TIMER1_A_PIN 16
|
#define TIMER1_A_PIN 16
|
||||||
#define TIMER1_B_PIN 17
|
#define TIMER1_B_PIN 17
|
||||||
#define TIMER1_ICP_PIN 17
|
#define TIMER1_ICP_PIN 17
|
||||||
#define TIMER3_A_PIN 3
|
#define TIMER3_A_PIN 3
|
||||||
#define TIMER3_B_PIN 4
|
#define TIMER3_B_PIN 4
|
||||||
#define TIMER3_ICP_PIN 4
|
#define TIMER3_ICP_PIN 4
|
||||||
|
|
||||||
// Arduino Mega
|
// Arduino Mega
|
||||||
//
|
//
|
||||||
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
|
||||||
#define TIMER1_A_PIN 11
|
#define TIMER1_A_PIN 11
|
||||||
#define TIMER1_B_PIN 12
|
#define TIMER1_B_PIN 12
|
||||||
#define TIMER1_C_PIN 13
|
#define TIMER1_C_PIN 13
|
||||||
#define TIMER3_A_PIN 5
|
#define TIMER3_A_PIN 5
|
||||||
#define TIMER3_B_PIN 2
|
#define TIMER3_B_PIN 2
|
||||||
#define TIMER3_C_PIN 3
|
#define TIMER3_C_PIN 3
|
||||||
#define TIMER4_A_PIN 6
|
#define TIMER4_A_PIN 6
|
||||||
#define TIMER4_B_PIN 7
|
#define TIMER4_B_PIN 7
|
||||||
#define TIMER4_C_PIN 8
|
#define TIMER4_C_PIN 8
|
||||||
#define TIMER4_ICP_PIN 49
|
#define TIMER4_ICP_PIN 49
|
||||||
#define TIMER5_A_PIN 46
|
#define TIMER5_A_PIN 46
|
||||||
#define TIMER5_B_PIN 45
|
#define TIMER5_B_PIN 45
|
||||||
#define TIMER5_C_PIN 44
|
#define TIMER5_C_PIN 44
|
||||||
#define TIMER3_ICP_PIN 48
|
#define TIMER3_ICP_PIN 48
|
||||||
#define TIMER3_CLK_PIN 47
|
#define TIMER3_CLK_PIN 47
|
||||||
|
|
||||||
// Arduino Leonardo, Yun, etc
|
// Arduino Leonardo, Yun, etc
|
||||||
//
|
//
|
||||||
#elif defined(__AVR_ATmega32U4__)
|
#elif defined(__AVR_ATmega32U4__)
|
||||||
#define TIMER1_A_PIN 9
|
#define TIMER1_A_PIN 9
|
||||||
#define TIMER1_B_PIN 10
|
#define TIMER1_B_PIN 10
|
||||||
#define TIMER1_C_PIN 11
|
#define TIMER1_C_PIN 11
|
||||||
#define TIMER1_ICP_PIN 4
|
#define TIMER1_ICP_PIN 4
|
||||||
#define TIMER1_CLK_PIN 12
|
#define TIMER1_CLK_PIN 12
|
||||||
#define TIMER3_A_PIN 5
|
#define TIMER3_A_PIN 5
|
||||||
#define TIMER3_ICP_PIN 13
|
#define TIMER3_ICP_PIN 13
|
||||||
|
|
||||||
// Uno, Duemilanove, LilyPad, etc
|
// Uno, Duemilanove, LilyPad, etc
|
||||||
//
|
//
|
||||||
#elif defined (__AVR_ATmega168__) || defined (__AVR_ATmega328P__)
|
#elif defined(__AVR_ATmega168__) || defined(__AVR_ATmega328P__)
|
||||||
#define TIMER1_A_PIN 9
|
#define TIMER1_A_PIN 9
|
||||||
#define TIMER1_B_PIN 10
|
#define TIMER1_B_PIN 10
|
||||||
#define TIMER1_ICP_PIN 8
|
#define TIMER1_ICP_PIN 8
|
||||||
#define TIMER1_CLK_PIN 5
|
#define TIMER1_CLK_PIN 5
|
||||||
|
|
||||||
// Sanguino
|
// Sanguino
|
||||||
//
|
//
|
||||||
#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__)
|
#elif defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644__)
|
||||||
#define TIMER1_A_PIN 13
|
#define TIMER1_A_PIN 13
|
||||||
#define TIMER1_B_PIN 12
|
#define TIMER1_B_PIN 12
|
||||||
#define TIMER1_ICP_PIN 14
|
#define TIMER1_ICP_PIN 14
|
||||||
#define TIMER1_CLK_PIN 1
|
#define TIMER1_CLK_PIN 1
|
||||||
|
|
||||||
// Wildfire - Wicked Devices
|
// Wildfire - Wicked Devices
|
||||||
//
|
//
|
||||||
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION >= 3
|
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION >= 3
|
||||||
#define TIMER1_A_PIN 5 // PD5
|
#define TIMER1_A_PIN 5 // PD5
|
||||||
#define TIMER1_B_PIN 8 // PD4
|
#define TIMER1_B_PIN 8 // PD4
|
||||||
#define TIMER1_ICP_PIN 6 // PD6
|
#define TIMER1_ICP_PIN 6 // PD6
|
||||||
#define TIMER1_CLK_PIN 23 // PB1
|
#define TIMER1_CLK_PIN 23 // PB1
|
||||||
#define TIMER3_A_PIN 12 // PB6
|
#define TIMER3_A_PIN 12 // PB6
|
||||||
#define TIMER3_B_PIN 13 // PB7
|
#define TIMER3_B_PIN 13 // PB7
|
||||||
#define TIMER3_ICP_PIN 9 // PB5
|
#define TIMER3_ICP_PIN 9 // PB5
|
||||||
#define TIMER3_CLK_PIN 0 // PD0
|
#define TIMER3_CLK_PIN 0 // PD0
|
||||||
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION < 3
|
#elif defined(__AVR_ATmega1284P__) && defined(WILDFIRE_VERSION) && WILDFIRE_VERSION < 3
|
||||||
#define TIMER1_A_PIN 5 // PD5
|
#define TIMER1_A_PIN 5 // PD5
|
||||||
#define TIMER1_B_PIN 4 // PD4
|
#define TIMER1_B_PIN 4 // PD4
|
||||||
#define TIMER1_ICP_PIN 6 // PD6
|
#define TIMER1_ICP_PIN 6 // PD6
|
||||||
#define TIMER1_CLK_PIN 15 // PB1
|
#define TIMER1_CLK_PIN 15 // PB1
|
||||||
#define TIMER3_A_PIN 12 // PB6
|
#define TIMER3_A_PIN 12 // PB6
|
||||||
#define TIMER3_B_PIN 13 // PB7
|
#define TIMER3_B_PIN 13 // PB7
|
||||||
#define TIMER3_ICP_PIN 11 // PB5
|
#define TIMER3_ICP_PIN 11 // PB5
|
||||||
#define TIMER3_CLK_PIN 0 // PD0
|
#define TIMER3_CLK_PIN 0 // PD0
|
||||||
|
|
||||||
// Mighty-1284 - Maniacbug
|
// Mighty-1284 - Maniacbug
|
||||||
//
|
//
|
||||||
#elif defined(__AVR_ATmega1284P__)
|
#elif defined(__AVR_ATmega1284P__)
|
||||||
#define TIMER1_A_PIN 12 // PD5
|
#define TIMER1_A_PIN 12 // PD5
|
||||||
#define TIMER1_B_PIN 13 // PD4
|
#define TIMER1_B_PIN 13 // PD4
|
||||||
#define TIMER1_ICP_PIN 14 // PD6
|
#define TIMER1_ICP_PIN 14 // PD6
|
||||||
#define TIMER1_CLK_PIN 1 // PB1
|
#define TIMER1_CLK_PIN 1 // PB1
|
||||||
#define TIMER3_A_PIN 6 // PB6
|
#define TIMER3_A_PIN 6 // PB6
|
||||||
#define TIMER3_B_PIN 7 // PB7
|
#define TIMER3_B_PIN 7 // PB7
|
||||||
#define TIMER3_ICP_PIN 5 // PB5
|
#define TIMER3_ICP_PIN 5 // PB5
|
||||||
#define TIMER3_CLK_PIN 8 // PD0
|
#define TIMER3_CLK_PIN 8 // PD0
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
84
src/pins.h
84
src/pins.h
|
@ -1,52 +1,52 @@
|
||||||
|
|
||||||
// For RAMPS 1.4
|
// For RAMPS 1.4
|
||||||
#define X_STEP_PIN 54
|
#define X_STEP_PIN 54
|
||||||
#define X_DIR_PIN 55
|
#define X_DIR_PIN 55
|
||||||
#define X_ENABLE_PIN 38
|
#define X_ENABLE_PIN 38
|
||||||
#define X_MIN_PIN 3
|
#define X_MIN_PIN 3
|
||||||
#define X_MAX_PIN 2
|
#define X_MAX_PIN 2
|
||||||
#define X_ENCDR_A 16
|
#define X_ENCDR_A 16
|
||||||
#define X_ENCDR_B 17
|
#define X_ENCDR_B 17
|
||||||
#define X_ENCDR_A_Q 31
|
#define X_ENCDR_A_Q 31
|
||||||
#define X_ENCDR_B_Q 33
|
#define X_ENCDR_B_Q 33
|
||||||
|
|
||||||
#define Y_STEP_PIN 60
|
#define Y_STEP_PIN 60
|
||||||
#define Y_DIR_PIN 61
|
#define Y_DIR_PIN 61
|
||||||
#define Y_ENABLE_PIN 56
|
#define Y_ENABLE_PIN 56
|
||||||
#define Y_MIN_PIN 14
|
#define Y_MIN_PIN 14
|
||||||
#define Y_MAX_PIN 15
|
#define Y_MAX_PIN 15
|
||||||
#define Y_ENCDR_A 23
|
#define Y_ENCDR_A 23
|
||||||
#define Y_ENCDR_B 25
|
#define Y_ENCDR_B 25
|
||||||
#define Y_ENCDR_A_Q 35
|
#define Y_ENCDR_A_Q 35
|
||||||
#define Y_ENCDR_B_Q 37
|
#define Y_ENCDR_B_Q 37
|
||||||
|
|
||||||
#define Z_STEP_PIN 46
|
#define Z_STEP_PIN 46
|
||||||
#define Z_DIR_PIN 48
|
#define Z_DIR_PIN 48
|
||||||
#define Z_ENABLE_PIN 62
|
#define Z_ENABLE_PIN 62
|
||||||
#define Z_MIN_PIN 18
|
#define Z_MIN_PIN 18
|
||||||
#define Z_MAX_PIN 19
|
#define Z_MAX_PIN 19
|
||||||
#define Z_ENCDR_A 27
|
#define Z_ENCDR_A 27
|
||||||
#define Z_ENCDR_B 29
|
#define Z_ENCDR_B 29
|
||||||
#define Z_ENCDR_A_Q 39
|
#define Z_ENCDR_A_Q 39
|
||||||
#define Z_ENCDR_B_Q 41
|
#define Z_ENCDR_B_Q 41
|
||||||
|
|
||||||
#define E_STEP_PIN 26
|
#define E_STEP_PIN 26
|
||||||
#define E_DIR_PIN 28
|
#define E_DIR_PIN 28
|
||||||
#define E_ENABLE_PIN 24
|
#define E_ENABLE_PIN 24
|
||||||
|
|
||||||
#define SDPOWER -1
|
#define SDPOWER -1
|
||||||
#define SDSS 53
|
#define SDSS 53
|
||||||
#define LED_PIN 13
|
#define LED_PIN 13
|
||||||
|
|
||||||
#define FAN_PIN 9
|
#define FAN_PIN 9
|
||||||
|
|
||||||
#define PS_ON_PIN 12
|
#define PS_ON_PIN 12
|
||||||
#define KILL_PIN -1
|
#define KILL_PIN -1
|
||||||
|
|
||||||
#define HEATER_0_PIN 10
|
#define HEATER_0_PIN 10
|
||||||
#define HEATER_1_PIN 8
|
#define HEATER_1_PIN 8
|
||||||
#define TEMP_0_PIN 13 // ANALOG NUMBERING
|
#define TEMP_0_PIN 13 // ANALOG NUMBERING
|
||||||
#define TEMP_1_PIN 14 // ANALOG NUMBERING
|
#define TEMP_1_PIN 14 // ANALOG NUMBERING
|
||||||
|
|
||||||
#define SERVO_0_PIN 4
|
#define SERVO_0_PIN 4
|
||||||
#define SERVO_1_PIN 5
|
#define SERVO_1_PIN 5
|
||||||
|
|
|
@ -1 +1 @@
|
||||||
// All code in farmbot_arduino_controller.cpp
|
// All code in farmbot_arduino_controller.cpp
|
||||||
|
|
|
@ -173,4 +173,4 @@
|
||||||
<UserProperties vm.programmer_name="avrisp" arduino.upload.port="COM3" />
|
<UserProperties vm.programmer_name="avrisp" arduino.upload.port="COM3" />
|
||||||
</VisualStudio>
|
</VisualStudio>
|
||||||
</ProjectExtensions>
|
</ProjectExtensions>
|
||||||
</Project>
|
</Project>
|
||||||
|
|
|
@ -261,4 +261,4 @@
|
||||||
<Filter>Header Files</Filter>
|
<Filter>Header Files</Filter>
|
||||||
</ClInclude>
|
</ClInclude>
|
||||||
</ItemGroup>
|
</ItemGroup>
|
||||||
</Project>
|
</Project>
|
||||||
|
|
Loading…
Reference in New Issue