* Merged code for setting axis to zero
* Disabled some new features and experimental encoder code * Added code from updating motor settings without rebootpull/66/head
parent
a0de45b586
commit
54c7516390
|
@ -122,6 +122,9 @@ CommandCodeEnum Command::getGCodeEnum(char* code) {
|
||||||
if (strcmp(code, "F83") == 0) {
|
if (strcmp(code, "F83") == 0) {
|
||||||
return F83;
|
return F83;
|
||||||
}
|
}
|
||||||
|
if (strcmp(code, "F84") == 0) {
|
||||||
|
return F84;
|
||||||
|
}
|
||||||
|
|
||||||
return CODE_UNDEFINED;
|
return CODE_UNDEFINED;
|
||||||
}
|
}
|
||||||
|
|
|
@ -31,7 +31,8 @@ enum CommandCodeEnum
|
||||||
F61 = 161,
|
F61 = 161,
|
||||||
F81 = 181,
|
F81 = 181,
|
||||||
F82 = 182,
|
F82 = 182,
|
||||||
F83 = 183
|
F83 = 183,
|
||||||
|
F84 = 184
|
||||||
};
|
};
|
||||||
|
|
||||||
//#define NULL 0
|
//#define NULL 0
|
||||||
|
|
|
@ -0,0 +1,49 @@
|
||||||
|
/*
|
||||||
|
* F84Handler.cpp
|
||||||
|
*
|
||||||
|
* Created on: 2017/04/13
|
||||||
|
* Author: Rick Carlino
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "F84Handler.h"
|
||||||
|
|
||||||
|
static F84Handler *instance;
|
||||||
|
const double DO_RESET = 1;
|
||||||
|
|
||||||
|
F84Handler *F84Handler::getInstance()
|
||||||
|
{
|
||||||
|
if (!instance)
|
||||||
|
{
|
||||||
|
instance = new F84Handler();
|
||||||
|
};
|
||||||
|
return instance;
|
||||||
|
};
|
||||||
|
|
||||||
|
F84Handler::F84Handler()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
int F84Handler::execute(Command *command)
|
||||||
|
{
|
||||||
|
|
||||||
|
if (command->getX() == DO_RESET)
|
||||||
|
{
|
||||||
|
Serial.println("R84 Will zero X");
|
||||||
|
CurrentState::getInstance()->setX(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (command->getY() == DO_RESET)
|
||||||
|
{
|
||||||
|
Serial.println("R84 Will zero Y");
|
||||||
|
CurrentState::getInstance()->setY(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (command->getZ() == DO_RESET)
|
||||||
|
{
|
||||||
|
Serial.println("R84 Will zero Z");
|
||||||
|
CurrentState::getInstance()->setZ(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -0,0 +1,31 @@
|
||||||
|
/*
|
||||||
|
* F84Handler.h
|
||||||
|
*
|
||||||
|
* Created on: 2017/4/13
|
||||||
|
* Author: Rick Carlino
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef F84HANDLER_H_
|
||||||
|
#define F84HANDLER_H_
|
||||||
|
#include "GCodeHandler.h"
|
||||||
|
#include "Config.h"
|
||||||
|
#include "CurrentState.h"
|
||||||
|
#include "pins.h"
|
||||||
|
#include "Config.h"
|
||||||
|
#include "StepperControl.h"
|
||||||
|
|
||||||
|
class F84Handler : public GCodeHandler
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
static F84Handler *getInstance();
|
||||||
|
int execute(Command *);
|
||||||
|
|
||||||
|
private:
|
||||||
|
F84Handler();
|
||||||
|
F84Handler(F84Handler const &);
|
||||||
|
void operator=(F84Handler const &);
|
||||||
|
long adjustStepAmount(long);
|
||||||
|
long getNumberOfSteps(double, double);
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif /* F84HANDLER_H_ */
|
|
@ -25,10 +25,15 @@ 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
|
||||||
|
|
||||||
|
// 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 ||
|
||||||
|
@ -44,6 +49,9 @@ int GCodeProcessor::execute(Command* command) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Return error when no command or invalid command is found
|
||||||
|
|
||||||
if(command == NULL) {
|
if(command == NULL) {
|
||||||
if(LOGGING) {
|
if(LOGGING) {
|
||||||
|
@ -59,6 +67,8 @@ int GCodeProcessor::execute(Command* command) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Get the right handler for this command
|
||||||
|
|
||||||
GCodeHandler* handler = getGCodeHandler(command->getCodeEnum());
|
GCodeHandler* handler = getGCodeHandler(command->getCodeEnum());
|
||||||
|
|
||||||
if(handler == NULL) {
|
if(handler == NULL) {
|
||||||
|
@ -66,6 +76,8 @@ int GCodeProcessor::execute(Command* command) {
|
||||||
return -1;
|
return -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 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();
|
||||||
|
|
||||||
|
@ -86,6 +98,10 @@ GCodeHandler* GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum) {
|
||||||
|
|
||||||
GCodeHandler* handler = NULL;
|
GCodeHandler* handler = NULL;
|
||||||
|
|
||||||
|
// These are if statements so they can be disabled as test
|
||||||
|
// Usefull when running into memory issues again
|
||||||
|
|
||||||
|
|
||||||
if (codeEnum == G00) {handler = G00Handler::getInstance();}
|
if (codeEnum == G00) {handler = G00Handler::getInstance();}
|
||||||
|
|
||||||
if (codeEnum == G28) {handler = G28Handler::getInstance();}
|
if (codeEnum == G28) {handler = G28Handler::getInstance();}
|
||||||
|
@ -110,67 +126,12 @@ GCodeHandler* GCodeProcessor::getGCodeHandler(CommandCodeEnum codeEnum) {
|
||||||
if (codeEnum == F43) {handler = F43Handler::getInstance();}
|
if (codeEnum == F43) {handler = F43Handler::getInstance();}
|
||||||
if (codeEnum == F44) {handler = F44Handler::getInstance();}
|
if (codeEnum == F44) {handler = F44Handler::getInstance();}
|
||||||
|
|
||||||
// if (codeEnum == F61) {handler = F61Handler::getInstance();}
|
if (codeEnum == F61) {handler = F61Handler::getInstance();}
|
||||||
|
|
||||||
if (codeEnum == F81) {handler = F81Handler::getInstance();}
|
if (codeEnum == F81) {handler = F81Handler::getInstance();}
|
||||||
if (codeEnum == F82) {handler = F82Handler::getInstance();}
|
if (codeEnum == F82) {handler = F82Handler::getInstance();}
|
||||||
if (codeEnum == F83) {handler = F83Handler::getInstance();}
|
if (codeEnum == F83) {handler = F83Handler::getInstance();}
|
||||||
|
if (codeEnum == F84) {handler = F84Handler::getInstance();}
|
||||||
|
|
||||||
/*
|
|
||||||
switch(codeEnum) {
|
|
||||||
case G00:
|
|
||||||
return G00Handler::getInstance();
|
|
||||||
case G28:
|
|
||||||
return G28Handler::getInstance();
|
|
||||||
|
|
||||||
case F11:
|
|
||||||
return F11Handler::getInstance();
|
|
||||||
case F12:
|
|
||||||
return F12Handler::getInstance();
|
|
||||||
case F13:
|
|
||||||
return F13Handler::getInstance();
|
|
||||||
|
|
||||||
case F14:
|
|
||||||
return F14Handler::getInstance();
|
|
||||||
case F15:
|
|
||||||
return F15Handler::getInstance();
|
|
||||||
case F16:
|
|
||||||
return F16Handler::getInstance();
|
|
||||||
|
|
||||||
case F20:
|
|
||||||
return F20Handler::getInstance();
|
|
||||||
case F21:
|
|
||||||
return F21Handler::getInstance();
|
|
||||||
case F22:
|
|
||||||
return F22Handler::getInstance();
|
|
||||||
|
|
||||||
case F31:
|
|
||||||
return F31Handler::getInstance();
|
|
||||||
case F32:
|
|
||||||
return F32Handler::getInstance();
|
|
||||||
|
|
||||||
case F41:
|
|
||||||
return F41Handler::getInstance();
|
|
||||||
case F42:
|
|
||||||
return F42Handler::getInstance();
|
|
||||||
case F43:
|
|
||||||
return F43Handler::getInstance();
|
|
||||||
case F44:
|
|
||||||
return F44Handler::getInstance();
|
|
||||||
|
|
||||||
case F61:
|
|
||||||
return F61Handler::getInstance();
|
|
||||||
|
|
||||||
case F81:
|
|
||||||
return F81Handler::getInstance();
|
|
||||||
case F82:
|
|
||||||
return F82Handler::getInstance();
|
|
||||||
case F83:
|
|
||||||
return F83Handler::getInstance();
|
|
||||||
|
|
||||||
}
|
|
||||||
*/
|
|
||||||
|
|
||||||
|
|
||||||
return handler;
|
return handler;
|
||||||
|
|
|
@ -35,11 +35,12 @@
|
||||||
#include "F43Handler.h"
|
#include "F43Handler.h"
|
||||||
#include "F44Handler.h"
|
#include "F44Handler.h"
|
||||||
|
|
||||||
//#include "F61Handler.h"
|
#include "F61Handler.h"
|
||||||
|
|
||||||
#include "F81Handler.h"
|
#include "F81Handler.h"
|
||||||
#include "F82Handler.h"
|
#include "F82Handler.h"
|
||||||
#include "F83Handler.h"
|
#include "F83Handler.h"
|
||||||
|
#include "F84Handler.h"
|
||||||
|
|
||||||
class GCodeProcessor {
|
class GCodeProcessor {
|
||||||
public:
|
public:
|
||||||
|
|
|
@ -16,6 +16,8 @@ ParameterList::ParameterList() {
|
||||||
// so during subsequent boots the values are just loaded from eeprom
|
// so during subsequent boots the values are just loaded from eeprom
|
||||||
// unless the eeprom is disabled with a parameter
|
// unless the eeprom is disabled with a parameter
|
||||||
|
|
||||||
|
int paramChangeNr = 0;
|
||||||
|
|
||||||
int paramVersion = readValueEeprom(0);
|
int paramVersion = readValueEeprom(0);
|
||||||
if (paramVersion <= 0) {
|
if (paramVersion <= 0) {
|
||||||
setAllValuesToDefault();
|
setAllValuesToDefault();
|
||||||
|
@ -58,6 +60,12 @@ int ParameterList::readValue(int id) {
|
||||||
|
|
||||||
int ParameterList::writeValue(int id, int value) {
|
int ParameterList::writeValue(int id, int value) {
|
||||||
|
|
||||||
|
if (paramChangeNr < 9999) {
|
||||||
|
paramChangeNr++;
|
||||||
|
} 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
|
// Store the value in memory
|
||||||
|
@ -114,6 +122,11 @@ int ParameterList::getValue(int id) {
|
||||||
return paramValues[id];
|
return paramValues[id];
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int ParameterList::paramChangeNumber() {
|
||||||
|
return paramChangeNr;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// ===== eeprom handling ====
|
// ===== eeprom handling ====
|
||||||
|
|
||||||
int ParameterList::readValueEeprom(int id) {
|
int ParameterList::readValueEeprom(int id) {
|
||||||
|
|
|
@ -129,10 +129,15 @@ public:
|
||||||
|
|
||||||
void sendConfigToModules();
|
void sendConfigToModules();
|
||||||
|
|
||||||
|
int paramChangeNumber();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
ParameterList();
|
ParameterList();
|
||||||
ParameterList(ParameterList const&);
|
ParameterList(ParameterList const&);
|
||||||
void operator=(ParameterList const&);
|
void operator=(ParameterList const&);
|
||||||
|
|
||||||
|
int paramChangeNr;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -81,6 +81,24 @@ StepperControl::StepperControl() {
|
||||||
axisY.label = 'Y';
|
axisY.label = 'Y';
|
||||||
axisZ.label = 'Z';
|
axisZ.label = 'Z';
|
||||||
|
|
||||||
|
// Create the encoder controller
|
||||||
|
|
||||||
|
encoderX = StepperControlEncoder();
|
||||||
|
encoderY = StepperControlEncoder();
|
||||||
|
encoderZ = StepperControlEncoder();
|
||||||
|
|
||||||
|
// Load settings
|
||||||
|
|
||||||
|
loadSettings();
|
||||||
|
|
||||||
|
|
||||||
|
motorMotorsEnabled = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void StepperControl::loadSettings() {
|
||||||
|
|
||||||
|
// Load motor settings
|
||||||
|
|
||||||
axisX.loadPinNumbers(X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, E_STEP_PIN, E_DIR_PIN, E_ENABLE_PIN);
|
axisX.loadPinNumbers(X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, E_STEP_PIN, E_DIR_PIN, E_ENABLE_PIN);
|
||||||
axisY.loadPinNumbers(Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, 0, 0, 0);
|
axisY.loadPinNumbers(Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, 0, 0, 0);
|
||||||
axisZ.loadPinNumbers(Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, 0, 0, 0);
|
axisZ.loadPinNumbers(Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, 0, 0, 0);
|
||||||
|
@ -90,12 +108,10 @@ StepperControl::StepperControl() {
|
||||||
axisSubStep[2] = COMM_REPORT_MOVE_STATUS_IDLE;
|
axisSubStep[2] = COMM_REPORT_MOVE_STATUS_IDLE;
|
||||||
|
|
||||||
loadMotorSettings();
|
loadMotorSettings();
|
||||||
loadEncoderSettings();
|
|
||||||
// Create the encoder controller
|
|
||||||
|
|
||||||
encoderX = StepperControlEncoder();
|
// Load encoder settings
|
||||||
encoderY = StepperControlEncoder();
|
|
||||||
encoderZ = StepperControlEncoder();
|
loadEncoderSettings();
|
||||||
|
|
||||||
encoderX.loadPinNumbers(X_ENCDR_A, X_ENCDR_B, X_ENCDR_A_Q, X_ENCDR_B_Q);
|
encoderX.loadPinNumbers(X_ENCDR_A, X_ENCDR_B, X_ENCDR_A_Q, X_ENCDR_B_Q);
|
||||||
encoderY.loadPinNumbers(Y_ENCDR_A, Y_ENCDR_B, Y_ENCDR_A_Q, Y_ENCDR_B_Q);
|
encoderY.loadPinNumbers(Y_ENCDR_A, Y_ENCDR_B, Y_ENCDR_A_Q, Y_ENCDR_B_Q);
|
||||||
|
@ -105,7 +121,6 @@ StepperControl::StepperControl() {
|
||||||
encoderY.loadSettings( motorConsEncoderType[1], motorConsEncoderScaling[1]);
|
encoderY.loadSettings( motorConsEncoderType[1], motorConsEncoderScaling[1]);
|
||||||
encoderZ.loadSettings( motorConsEncoderType[2], motorConsEncoderScaling[2]);
|
encoderZ.loadSettings( motorConsEncoderType[2], motorConsEncoderScaling[2]);
|
||||||
|
|
||||||
motorMotorsEnabled = false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControl::test() {
|
void StepperControl::test() {
|
||||||
|
@ -117,6 +132,13 @@ void StepperControl::test() {
|
||||||
Serial.print(encoderX.currentPosition());
|
Serial.print(encoderX.currentPosition());
|
||||||
Serial.print("\r\n");
|
Serial.print("\r\n");
|
||||||
|
|
||||||
|
Serial.print("R99");
|
||||||
|
Serial.print(" mot y = ");
|
||||||
|
Serial.print(axisY.currentPosition());
|
||||||
|
Serial.print(" enc y = ");
|
||||||
|
Serial.print(encoderY.currentPosition());
|
||||||
|
Serial.print("\r\n");
|
||||||
|
|
||||||
|
|
||||||
// read changes in encoder
|
// read changes in encoder
|
||||||
//encoderX.readEncoder();
|
//encoderX.readEncoder();
|
||||||
|
|
|
@ -42,6 +42,7 @@ public:
|
||||||
bool motorsEnabled();
|
bool motorsEnabled();
|
||||||
|
|
||||||
void storePosition();
|
void storePosition();
|
||||||
|
void loadSettings();
|
||||||
|
|
||||||
void test();
|
void test();
|
||||||
void test2();
|
void test2();
|
||||||
|
|
|
@ -109,12 +109,18 @@ void StepperControlEncoder::readEncoder() {
|
||||||
|
|
||||||
void StepperControlEncoder::readChannels() {
|
void StepperControlEncoder::readChannels() {
|
||||||
|
|
||||||
|
// 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);
|
||||||
|
|
||||||
|
// Tim 2017-04-15 Experimental code disabled
|
||||||
|
|
||||||
|
/*
|
||||||
if (encoderType == 1) {
|
if (encoderType == 1) {
|
||||||
|
|
||||||
// differential encoder
|
// differential encoder
|
||||||
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ)) {
|
if ((readChannelA ^ readChannelAQ) && (readChannelB ^ readChannelBQ)) {
|
||||||
curValChannelA = readChannelA;
|
curValChannelA = readChannelA;
|
||||||
|
@ -122,11 +128,13 @@ void StepperControlEncoder::readChannels() {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
|
||||||
// encoderType <= 0
|
// encoderType <= 0
|
||||||
// non-differential incremental encoder
|
// non-differential incremental encoder
|
||||||
curValChannelA = readChannelA;
|
curValChannelA = readChannelA;
|
||||||
curValChannelB = readChannelB;
|
curValChannelB = readChannelB;
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
|
|
||||||
// curValChannelA = readChannelA;
|
// curValChannelA = readChannelA;
|
||||||
// curValChannelB = readChannelB;
|
// curValChannelB = readChannelB;
|
||||||
|
@ -137,6 +145,9 @@ void StepperControlEncoder::readChannels() {
|
||||||
}
|
}
|
||||||
|
|
||||||
void StepperControlEncoder::shiftChannels() {
|
void StepperControlEncoder::shiftChannels() {
|
||||||
|
|
||||||
|
// Save the current enoder status to later on compare with new values
|
||||||
|
|
||||||
prvValChannelA = curValChannelA;
|
prvValChannelA = curValChannelA;
|
||||||
prvValChannelB = curValChannelB;
|
prvValChannelB = curValChannelB;
|
||||||
}
|
}
|
||||||
|
|
|
@ -3,7 +3,7 @@
|
||||||
#include "pins.h"
|
#include "pins.h"
|
||||||
#include "Config.h"
|
#include "Config.h"
|
||||||
#include "StepperControl.h"
|
#include "StepperControl.h"
|
||||||
//#include "ServoControl.h"
|
#include "ServoControl.h"
|
||||||
#include "PinGuard.h"
|
#include "PinGuard.h"
|
||||||
#include "TimerOne.h"
|
#include "TimerOne.h"
|
||||||
#include "MemoryFree.h"
|
#include "MemoryFree.h"
|
||||||
|
@ -15,6 +15,8 @@ static GCodeProcessor* gCodeProcessor = new GCodeProcessor();
|
||||||
unsigned long lastAction;
|
unsigned long lastAction;
|
||||||
unsigned long currentTime;
|
unsigned long currentTime;
|
||||||
|
|
||||||
|
int lastParamChangeNr = 0;
|
||||||
|
|
||||||
String commandString = "";
|
String commandString = "";
|
||||||
char incomingChar = 0;
|
char incomingChar = 0;
|
||||||
char incomingCommandArray[INCOMING_CMD_BUF_SIZE];
|
char incomingCommandArray[INCOMING_CMD_BUF_SIZE];
|
||||||
|
@ -105,7 +107,7 @@ void setup() {
|
||||||
// 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 moviing
|
// 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
|
||||||
|
|
||||||
|
@ -180,6 +182,22 @@ void loop() {
|
||||||
|
|
||||||
//StepperControl::getInstance()->test();
|
//StepperControl::getInstance()->test();
|
||||||
|
|
||||||
|
// Check if parameters are changes, and if so load the new settings
|
||||||
|
|
||||||
|
if (lastParamChangeNr != ParameterList::getInstance()->paramChangeNumber()) {
|
||||||
|
lastParamChangeNr = ParameterList::getInstance()->paramChangeNumber();
|
||||||
|
|
||||||
|
Serial.print(COMM_REPORT_COMMENT);
|
||||||
|
Serial.print(" loading parameters ");
|
||||||
|
CurrentState::getInstance()->printQAndNewLine();
|
||||||
|
|
||||||
|
StepperControl::getInstance()->loadSettings();
|
||||||
|
PinGuard::getInstance()->loadConfig();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Do periodic checks and feedback
|
||||||
|
|
||||||
currentTime = millis();
|
currentTime = millis();
|
||||||
if (currentTime < lastAction) {
|
if (currentTime < lastAction) {
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue