From 8c9b2fe12843d9916405da804e0d17a1bd60423e Mon Sep 17 00:00:00 2001 From: madgrizzle Date: Tue, 20 Aug 2019 10:48:58 -0400 Subject: [PATCH 01/14] Add Missing Kinematics.Init() Any changes to values that are used during the kinematics::forward calculations should call kinematics.init() so sled position can be recalculated. If its not, this can cause a "sled not keeping up" error, particularly after calibration. If the sled is at an unadjusted position and a move is made, the move will be made with the adjusted parameters and that can exceed the positionErrorLimit. --- cnc_ctrl_v1/Settings.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index b86af643..065a016a 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -382,6 +382,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 37: sysSettings.chainSagCorrection = value; + kinematics.init(); break; case 38: settingsSaveStepstoEEprom(); @@ -400,9 +401,11 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 40: sysSettings.leftChainTolerance = value; + kinematics.init(); break; case 41: sysSettings.rightChainTolerance = value; + kinematics.init(); break; case 42: sysSettings.positionErrorLimit = value; From 7748db8e3de18e3a3a0daaf4cbbe9226703aeae9 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Wed, 21 Aug 2019 19:05:01 -0700 Subject: [PATCH 02/14] add B99 command to control FAKE_SERVO mode cnc_ctrl_v1.ino: - add global flag to signal Axis::computePID() and Motor::write() - check for saved state at startup and report it Gcode.cpp: - add 'B99 ' command - - if the line contains 'ON' set FAKE_SERVO_STATE otherwise clear it - - report the state - - save the value of FAKE_SERVO_STATE in the high byte of EEPROM to persiste over restarts - - note that Setings::settingsWipe(SETTINGS_RESTORE_ALL) writes '0' to that location, which turns FAKE_SERVO off Axis.cpp: - at start of Axis::computePID(), check 'if (FAKE_SERVO_STATE != 0)' to determine whether to fake the encoder change. The check adds very few microseconds to this importrant function. Motor.cpp: - at the start of Motor::write() add a check for (FAKE_SERVO_STATE == 0) to determine whether to set the speed of the motor. This check adds only a few microseconds. Adding this check keeps the motors inoperative dureing FAKE_SERVO mode. --- cnc_ctrl_v1/Axis.cpp | 15 ++++++++------- cnc_ctrl_v1/Config.h | 9 ++++++--- cnc_ctrl_v1/GCode.cpp | 31 ++++++++++++++++++++++++++++++- cnc_ctrl_v1/GCode.h | 1 + cnc_ctrl_v1/Motor.cpp | 2 +- cnc_ctrl_v1/cnc_ctrl_v1.ino | 10 ++++++++++ 6 files changed, 56 insertions(+), 12 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index 5bbe8063..dac438df 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -17,6 +17,7 @@ #include "Maslow.h" +// #include void Axis::setup(const int& pwmPin, const int& directionPin1, const int& directionPin2, const int& encoderPin1, const int& encoderPin2, const char& axisName, const unsigned long& loopInterval) { @@ -84,14 +85,14 @@ void Axis::setSteps(const long& steps){ void Axis::computePID(){ - #ifdef FAKE_SERVO - if (motorGearboxEncoder.motor.attached()){ - // Adds up to 10% error just to simulate servo noise - double rpm = (-1 * _pidOutput) * random(90, 110) / 100; - unsigned long steps = motorGearboxEncoder.encoder.read() + round( rpm * *_encoderSteps * LOOPINTERVAL)/(60 * 1000000); - motorGearboxEncoder.encoder.write(steps); + if (FAKE_SERVO_STATE != 0) { + if (motorGearboxEncoder.motor.attached()){ + // Adds up to 10% error just to simulate servo noise + double rpm = (-1 * _pidOutput) * random(90, 110) / 100; + unsigned long steps = motorGearboxEncoder.encoder.read() + round( rpm * *_encoderSteps * LOOPINTERVAL)/(60 * 1000000); + motorGearboxEncoder.encoder.write(steps); + } } - #endif if (_disableAxisForTesting || !motorGearboxEncoder.motor.attached()){ return; diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index 64f4fe10..b7084d91 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -25,9 +25,12 @@ // LOOPINTERVAL tuning #define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging -// #define FAKE_SERVO // Uncomment this line to cause the Firmware to mimic - // a servo updating the encoder steps even if no servo - // is connected. Useful for testing on an arduino only +#define FAKE_SERVO 4095 // store the state of FAKE_SERVO in EEPROM[ 4095 ] to preserve + // the state of FAKE_SERVO mode over resets. + // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', + // 'B99' with no parameter, or any parameter other than 'ON' + // puts a '0' in that location and turns FAKE_SERVO mode off. + // Useful for testing on an arduino only (e.g. without motors). // #define SIMAVR // Uncomment this if you plan to run the Firmware in the simavr // simulator. Normally, you would not define this directly, but diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index fb1d908b..7a5b50cf 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -19,6 +19,7 @@ Copyright 2014-2017 Bar Smith*/ // commands #include "Maslow.h" +#include maslowRingBuffer incSerialBuffer; String readyCommandString = ""; //KRK why is this a global? @@ -367,7 +368,35 @@ byte executeBcodeLine(const String& gcodeLine){ return STATUS_OK; } - return STATUS_INVALID_STATEMENT; + + // Use 'B99 ON' to set FAKE_SERVO mode on, + // 'B99' with no parameter, or any parameter other than 'ON' + // turns FAKE_SERVO mode off. + // FAKE_SERVO mode causes the Firmware to mimic a servo, + // updating the encoder steps even if no servo is connected. + // Useful for testing on an arduino only (e.g. without motors). + // The status of FAKE_SERVO mode is stored in EEPROM[ 4095 ] + // to persist between resets. Tthat byte is set to '1' when FAKE_SERVO + // is on, '0' when off. settingsWipe(SETTINGS_RESTORE_ALL) clears the + // EEPROM to '0', sothat stores '0' at EEPROM[ 4095 ] as well. + if(gcodeLine.substring(0, 3) == "B99") { + int letterO = gcodeLine.indexOf('O'); + int letterN = gcodeLine.indexOf('N'); + if ((letterO != -1) && (letterN != -1)) { + EEPROM[ FAKE_SERVO ] = 1; + FAKE_SERVO_STATE = 1; + } else { + EEPROM[ FAKE_SERVO ] = 0; + FAKE_SERVO_STATE = 0; + } + if (FAKE_SERVO_STATE == 0) { + Serial.println(F("FAKE_SERVO off")); + } else { + Serial.println(F("FAKE_SERVO on")); + } + return(STATUS_OK); + } + return STATUS_INVALID_STATEMENT; } void executeGcodeLine(const String& gcodeLine){ diff --git a/cnc_ctrl_v1/GCode.h b/cnc_ctrl_v1/GCode.h index d2cf12f4..880a601d 100644 --- a/cnc_ctrl_v1/GCode.h +++ b/cnc_ctrl_v1/GCode.h @@ -46,5 +46,6 @@ void G38(const String&); void setInchesToMillimetersConversion(float); extern int SpindlePowerControlPin; extern int ProbePin; +extern int FAKE_SERVO_STATE; #endif diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index b2e40d34..a06b322a 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -113,7 +113,7 @@ void Motor::write(int speed, bool force){ /* Sets motor speed from input. Speed = 0 is stopped, -255 is full reverse, 255 is full ahead. If force is true the motor attached state will be ignored */ - if (_attachedState == 1 or force){ + if ((_attachedState == 1 or force) and (FAKE_SERVO_STATE == 0)){ speed = constrain(speed, -255, 255); _lastSpeed = speed; //saves speed for use in additive write bool forward = (speed > 0); diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index e844c51c..b4a1f1b2 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -35,6 +35,7 @@ // TLE5206 version #include "Maslow.h" +#include // Define system global state structure system_t sys; @@ -45,6 +46,9 @@ settings_t sysSettings; // Global realtime executor bitflag variable for setting various alarms. byte systemRtExecAlarm; +// Define global flag for FAKE_SERVO state +int FAKE_SERVO_STATE = 0; + // Define axes, it might be tighter to define these within the sys struct Axis leftAxis; Axis rightAxis; @@ -63,6 +67,12 @@ void setup(){ Serial.println(F(" Detected")); sys.inchesToMMConversion = 1; sys.writeStepsToEEPROM = false; + FAKE_SERVO_STATE = EEPROM[ FAKE_SERVO ] & B00000001; + if (FAKE_SERVO_STATE == 0) { + Serial.println(F("FAKE_SERVO off")); + } else { + Serial.println(F("FAKE_SERVO on")); + } settingsLoadFromEEprom(); sys.feedrate = sysSettings.maxFeed / 2.0; setupAxes(); From 5d351a32a277d6991b65dad804b12c6d71367eda Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Thu, 29 Aug 2019 22:50:30 -0700 Subject: [PATCH 03/14] tighten up FAKE_SERVO access - define a specific number value to indicate FAKE_SERVO as active in Config.h - in cnc_ctrl_v1 on startup, check the contents of EEPROM[ 4095 ] for that special value, if found enter FAKE_SERVO but if any othe value is found store a '0' there and indicate that FAKE_SERVO is 'off' - change the logic in Axis::computePID() and Motor::write() to check for the specific value ranther than non-zero. --- cnc_ctrl_v1/Axis.cpp | 2 +- cnc_ctrl_v1/Config.h | 3 ++- cnc_ctrl_v1/GCode.cpp | 12 ++++++------ cnc_ctrl_v1/Motor.cpp | 2 +- cnc_ctrl_v1/cnc_ctrl_v1.ino | 13 +++++++------ 5 files changed, 17 insertions(+), 15 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index dac438df..c03f9fda 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -85,7 +85,7 @@ void Axis::setSteps(const long& steps){ void Axis::computePID(){ - if (FAKE_SERVO_STATE != 0) { + if (FAKE_SERVO_STATE == FAKE_SERVO_PERMITTED) { if (motorGearboxEncoder.motor.attached()){ // Adds up to 10% error just to simulate servo noise double rpm = (-1 * _pidOutput) * random(90, 110) / 100; diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index b7084d91..89966499 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -25,7 +25,8 @@ // LOOPINTERVAL tuning #define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging -#define FAKE_SERVO 4095 // store the state of FAKE_SERVO in EEPROM[ 4095 ] to preserve +#define FAKE_SERVO_PERMITTED 42 // store this value +#define FAKE_SERVO 4095 // in EEPROM[ 4095 ] to preserve // the state of FAKE_SERVO mode over resets. // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', // 'B99' with no parameter, or any parameter other than 'ON' diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 7a5b50cf..826f7228 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -376,23 +376,23 @@ byte executeBcodeLine(const String& gcodeLine){ // updating the encoder steps even if no servo is connected. // Useful for testing on an arduino only (e.g. without motors). // The status of FAKE_SERVO mode is stored in EEPROM[ 4095 ] - // to persist between resets. Tthat byte is set to '1' when FAKE_SERVO + // to persist between resets. That byte is set to 'FAKE_SERVO_PERMITTED' when FAKE_SERVO // is on, '0' when off. settingsWipe(SETTINGS_RESTORE_ALL) clears the // EEPROM to '0', sothat stores '0' at EEPROM[ 4095 ] as well. if(gcodeLine.substring(0, 3) == "B99") { int letterO = gcodeLine.indexOf('O'); int letterN = gcodeLine.indexOf('N'); if ((letterO != -1) && (letterN != -1)) { - EEPROM[ FAKE_SERVO ] = 1; - FAKE_SERVO_STATE = 1; + EEPROM[ FAKE_SERVO ] = FAKE_SERVO_PERMITTED; + FAKE_SERVO_STATE = FAKE_SERVO_PERMITTED; } else { EEPROM[ FAKE_SERVO ] = 0; FAKE_SERVO_STATE = 0; } - if (FAKE_SERVO_STATE == 0) { - Serial.println(F("FAKE_SERVO off")); - } else { + if (FAKE_SERVO_STATE == FAKE_SERVO_PERMITTED) { Serial.println(F("FAKE_SERVO on")); + } else { + Serial.println(F("FAKE_SERVO off")); } return(STATUS_OK); } diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index a06b322a..a4e53a86 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -113,7 +113,7 @@ void Motor::write(int speed, bool force){ /* Sets motor speed from input. Speed = 0 is stopped, -255 is full reverse, 255 is full ahead. If force is true the motor attached state will be ignored */ - if ((_attachedState == 1 or force) and (FAKE_SERVO_STATE == 0)){ + if ((_attachedState == 1 or force) and (FAKE_SERVO_STATE != FAKE_SERVO_PERMITTED)){ speed = constrain(speed, -255, 255); _lastSpeed = speed; //saves speed for use in additive write bool forward = (speed > 0); diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index b4a1f1b2..4ba52ad3 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -67,12 +67,13 @@ void setup(){ Serial.println(F(" Detected")); sys.inchesToMMConversion = 1; sys.writeStepsToEEPROM = false; - FAKE_SERVO_STATE = EEPROM[ FAKE_SERVO ] & B00000001; - if (FAKE_SERVO_STATE == 0) { - Serial.println(F("FAKE_SERVO off")); - } else { - Serial.println(F("FAKE_SERVO on")); - } + FAKE_SERVO_STATE = EEPROM[ FAKE_SERVO ]; + if (FAKE_SERVO_STATE == FAKE_SERVO_PERMITTED) { // only this value is accepted + Serial.println(F("FAKE_SERVO on")); // to turn this on + } else { + Serial.println(F("FAKE_SERVO off")); // otherwise + EEPROM[ FAKE_SERVO ] = 0; // force it to the 'off' value + } settingsLoadFromEEprom(); sys.feedrate = sysSettings.maxFeed / 2.0; setupAxes(); From dc6c23f88b6735b9ce342b8c0d9bd10e2b82b1a9 Mon Sep 17 00:00:00 2001 From: Scott Smith Date: Sat, 5 Oct 2019 23:08:45 -0700 Subject: [PATCH 04/14] remove characters within a comment Remove comment characters between parentheses. --- cnc_ctrl_v1/GCode.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 826f7228..dc8b86df 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -566,6 +566,9 @@ void sanitizeCommandString(String& cmdString){ cmdString.remove(pos, 1); if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); } } + else { + cmdString.remove(pos, 1); + } } else { if (cmdString[pos] < ' ') { From 2ed6fff3012341365a2f0cca4d3ac704d94e3eec Mon Sep 17 00:00:00 2001 From: tinker Date: Tue, 25 Feb 2020 10:29:43 -0800 Subject: [PATCH 05/14] gb0101010101-g2-arc-z-optional: Do not perform Z axis movement on G2 if Z is not specified in gcode line. Set Z1 and Z2 to NAN if not provided. Update arc() to deal with NAN Z. Make Z calculations happen the same way as X&Y before movementUpdate(). Add Z end move same as X & Y. --- cnc_ctrl_v1/GCode.cpp | 8 +++++- cnc_ctrl_v1/Motion.cpp | 62 ++++++++++++++++++++++++++---------------- 2 files changed, 46 insertions(+), 24 deletions(-) diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index dc8b86df..3e47c9d5 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -20,6 +20,7 @@ Copyright 2014-2017 Bar Smith*/ #include "Maslow.h" #include +#include "math.h" maslowRingBuffer incSerialBuffer; String readyCommandString = ""; //KRK why is this a global? @@ -779,7 +780,8 @@ void G2(const String& readString, int G2orG3){ float X2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', X1/sys.inchesToMMConversion); float Y2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', Y1/sys.inchesToMMConversion); - float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', Z1/sys.inchesToMMConversion); + // Read target Z position from gcode. If it is not specified then set it to NAN so it will not be used. + float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', NAN); float I = sys.inchesToMMConversion*extractGcodeValue(readString, 'I', 0.0); float J = sys.inchesToMMConversion*extractGcodeValue(readString, 'J', 0.0); sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); @@ -789,6 +791,10 @@ void G2(const String& readString, int G2orG3){ sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm + // If there is no target Z (Z2) then set Z1 to be NAN so it is not used. + if (isnan(Z2)) { + Z1 = Z2; + } if (G2orG3 == 2){ arc(X1, Y1, Z1, X2, Y2, Z2, centerX, centerY, sys.feedrate, CLOCKWISE); } diff --git a/cnc_ctrl_v1/Motion.cpp b/cnc_ctrl_v1/Motion.cpp index 358dc222..a0b80e7b 100644 --- a/cnc_ctrl_v1/Motion.cpp +++ b/cnc_ctrl_v1/Motion.cpp @@ -237,7 +237,7 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co */ - //compute geometry + // Compute geometry. float pi = 3.1415; float radius = sqrt( sq(centerX - X1) + sq(centerY - Y1) ); float circumference = 2.0*pi*radius; @@ -245,12 +245,18 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co float startingAngle = atan2(Y1 - centerY, X1 - centerX); float endingAngle = atan2(Y2 - centerY, X2 - centerX); - // compute chord height of arc + // Compute chord height of arc. float chordSquared = sqrt(sq(X2 - X1) + sq(Y2 - Y1)); float tau = sqrt( sq(radius) - (chordSquared/4.0)); float chordHeight = radius - tau; - //compute angle between lines + // Determine if Z axis will be used. + bool useZ = true; + if (isnan(Z1) || isnan(Z2) || !sysSettings.zAxisAttached) { + useZ = false; + } + + // Compute angle between lines. float theta = endingAngle - startingAngle; if (direction == COUNTERCLOCKWISE){ if (theta <= 0){ @@ -269,7 +275,10 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co // In either case, the gcode cut was essentially a straight line, so // Replace it with a G1 cut to the endpoint String gcodeSubstitution = "G1 X"; - gcodeSubstitution = gcodeSubstitution + String(X2 / sys.inchesToMMConversion, 3) + " Y" + String(Y2 / sys.inchesToMMConversion, 3) + " Z" + String(Z2 / sys.inchesToMMConversion, 3) + " "; + gcodeSubstitution += String(X2 / sys.inchesToMMConversion, 3) + " Y" + String(Y2 / sys.inchesToMMConversion, 3); + if (useZ) { + gcodeSubstitution += " Z" + String(Z2 / sys.inchesToMMConversion, 3) + " "; + } Serial.println("Large-radius arc replaced by straight line to improve accuracy: " + gcodeSubstitution); G1(gcodeSubstitution, 1); return 1; @@ -287,32 +296,37 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co long finalNumberOfSteps = arcLengthMM/stepSizeMM; float delayTime = LOOPINTERVAL; - float zFeedRate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); - float zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); - // float zStepSizeMM = computeStepSize(zMaxFeed); - float zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; + float zFeedRate, zMaxFeed, zStepSizeMM; + + if (useZ) { + zFeedRate = calculateFeedrate(fabs(zDistanceToMoveInMM/finalNumberOfSteps), delayTime); + zMaxFeed = sysSettings.maxZRPM * abs(zAxis.getPitch()); + // zStepSizeMM = computeStepSize(zMaxFeed); + zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; - if (zFeedRate > zMaxFeed){ - zStepSizeMM = computeStepSize(zMaxFeed); - finalNumberOfSteps = fabs(zDistanceToMoveInMM/zStepSizeMM); - stepSizeMM = arcLengthMM/finalNumberOfSteps; - feedMMPerMin = calculateFeedrate(stepSizeMM, delayTime); + if (zFeedRate > zMaxFeed){ + // Recalculate all movement to fit within zMaxFeed parameter. + zStepSizeMM = computeStepSize(zMaxFeed); + finalNumberOfSteps = fabs(zDistanceToMoveInMM/zStepSizeMM); + stepSizeMM = arcLengthMM/finalNumberOfSteps; + feedMMPerMin = calculateFeedrate(stepSizeMM, delayTime); + } + + zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; } - - zStepSizeMM = zDistanceToMoveInMM/finalNumberOfSteps; - //Compute the starting position + // Compute the starting position. float angleNow = startingAngle; float degreeComplete = 0.0; float aChainLength; float bChainLength; - float zPosition = Z1 + zStepSizeMM; + float zPosition = Z1; - //attach the axes + // Attach the axes. leftAxis.attach(); rightAxis.attach(); - if (sysSettings.zAxisAttached) { + if (useZ) { zAxis.attach(); } @@ -335,17 +349,16 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co leftAxis.write(aChainLength); rightAxis.write(bChainLength); - if(sysSettings.zAxisAttached){ + if(useZ){ + zPosition += zStepSizeMM; zAxis.write(zPosition); } movementUpdate(); - // Run realtime commands + // Run real-time commands. execSystemRealtime(); if (sys.stop){return 1;} - numberOfStepsTaken++; - zPosition += zStepSizeMM; } } #if misloopDebug > 0 @@ -355,6 +368,9 @@ int arc(const float& X1, const float& Y1, const float& Z1, const float& X2, co kinematics.inverse(X2,Y2,&aChainLength,&bChainLength); leftAxis.endMove(aChainLength); rightAxis.endMove(bChainLength); + if (useZ) { + zAxis.endMove(Z2); + } sys.xPosition = X2; sys.yPosition = Y2; From 12af38cc34250622299e116b77ce2b6d8cda2df5 Mon Sep 17 00:00:00 2001 From: tinker Date: Fri, 15 May 2020 11:56:27 -0700 Subject: [PATCH 06/14] Add support for G2 & G3 commands that use radius R instead of I & J. --- cnc_ctrl_v1/GCode.cpp | 31 +++++++++++++++++++++++++++++++ 1 file changed, 31 insertions(+) diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 3e47c9d5..a1de371b 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -782,6 +782,7 @@ void G2(const String& readString, int G2orG3){ float Y2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', Y1/sys.inchesToMMConversion); // Read target Z position from gcode. If it is not specified then set it to NAN so it will not be used. float Z2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', NAN); + float R = sys.inchesToMMConversion*extractGcodeValue(readString, 'R', NAN); float I = sys.inchesToMMConversion*extractGcodeValue(readString, 'I', 0.0); float J = sys.inchesToMMConversion*extractGcodeValue(readString, 'J', 0.0); sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); @@ -789,6 +790,36 @@ void G2(const String& readString, int G2orG3){ float centerX = X1 + I; float centerY = Y1 + J; + // Calculate center point using radius R if it is provided. + if (!isnan(R) && R && (X2 != X1 || Y2 != Y1)) { + // e: clockwise -1, counterclockwise 1 + const float e = (G2orG3 == 2) ? -1 : 1, + // X and Y differences + dx = X2 - X1, + dy = Y2 - Y1, + // Linear distance between the points. + d = hypot(dx, dy), + // Distance to the arc pivot-point. + h = sqrt(sq(R) - sq(d * 0.5)), + // Point between the two points. + mx = (X1 + X2) * 0.5, + my = (Y1 + Y2) * 0.5, + // Slope of the perpendicular bisector. + sx = -dy / d, + sy = dx / d; + // Pivot-point of the arc. + centerX = mx + e * h * sx; + centerY = my + e * h * sy; + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("G0")); + Serial.print(G2orG3); + Serial.print(F(" Radius center: ")); + Serial.print(centerX); + Serial.print(F(",")); + Serial.println(centerY); + #endif + } + sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm // If there is no target Z (Z2) then set Z1 to be NAN so it is not used. From 408b4d93d5bfded7d5b2ed6d7ad567179c23d3c4 Mon Sep 17 00:00:00 2001 From: Ramon Arias Date: Mon, 18 May 2020 08:55:13 -0500 Subject: [PATCH 07/14] Z Axis limits I have made some small tweaks to the code to be able to set upper and lower limits for the z axis in order to prevent motors from forcing the Z Axis beyond its limits. --- cnc_ctrl_v1/Axis.cpp | 56 +++++++++++++++++++++++++++++++++++++--- cnc_ctrl_v1/GCode.cpp | 52 ++++++++++++++++++++++++++++++++++++- cnc_ctrl_v1/Settings.cpp | 2 ++ cnc_ctrl_v1/Settings.h | 2 ++ pull_request_template.md | 43 ++++++++++++++++++++++++++++++ 5 files changed, 151 insertions(+), 4 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index c03f9fda..514712a4 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -44,9 +44,25 @@ void Axis::initializePID(const unsigned long& loopInterval){ } void Axis::write(const float& targetPosition){ - _timeLastMoved = millis(); - _pidSetpoint = targetPosition/ *_mmPerRotation; - return; + + // Check that the Z axis position is withing limits stecified in Settings + + if(_axisName == 'Z'){ + if(!isnan(sysSettings.zAxisUpperLimit) && targetPosition > sysSettings.zAxisUpperLimit){ + _pidSetpoint = sysSettings.zAxisUpperLimit/ *_mmPerRotation; + return; + } + + if(!isnan(sysSettings.zAxisLowerLimit) && targetPosition < sysSettings.zAxisLowerLimit){ + _pidSetpoint = sysSettings.zAxisLowerLimit/ *_mmPerRotation; + return; + } + } + + // update target position + _timeLastMoved = millis(); + _pidSetpoint = targetPosition/ *_mmPerRotation; + return; } float Axis::read(){ @@ -62,9 +78,27 @@ float Axis::setpoint(){ void Axis::set(const float& newAxisPosition){ + // update the zAxis upper and lower limits relative to the new axis position + + if(_axisName == 'Z'){ + if(!isnan(sysSettings.zAxisUpperLimit)){ + sysSettings.zAxisUpperLimit += newAxisPosition - read(); + } + + if(!isnan(sysSettings.zAxisLowerLimit)){ + sysSettings.zAxisLowerLimit += newAxisPosition - read(); + } + + if(!isnan(sysSettings.zAxisUpperLimit) || !isnan(sysSettings.zAxisLowerLimit)){ + settingsSaveToEEprom(); + } + } + //reset everything to the new value _pidSetpoint = newAxisPosition/ *_mmPerRotation; motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); + + } @@ -225,11 +259,27 @@ void Axis::detachIfIdle(){ void Axis::endMove(const float& finalTarget){ + + // Check that the Z axis position is withing limits stecified in Settings + + if(_axisName == 'Z'){ + if(!isnan(sysSettings.zAxisUpperLimit) && finalTarget > sysSettings.zAxisUpperLimit){ + _pidSetpoint = sysSettings.zAxisUpperLimit/ *_mmPerRotation; + return; + } + + if(!isnan(sysSettings.zAxisLowerLimit) && finalTarget < sysSettings.zAxisLowerLimit){ + _pidSetpoint = sysSettings.zAxisLowerLimit/ *_mmPerRotation; + return; + } + } + _timeLastMoved = millis(); _pidSetpoint = finalTarget/ *_mmPerRotation; } + void Axis::stop(){ /* diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 3e47c9d5..f1198efc 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -370,6 +370,56 @@ byte executeBcodeLine(const String& gcodeLine){ return STATUS_OK; } + if(gcodeLine.substring(0, 3) == "B17"){ + //The B17 sets the current Z position as Upper Limit for zAxis + + sysSettings.zAxisUpperLimit = zAxis.read(); + settingsSaveToEEprom(); + + Serial.print("Upper limit set to: "); + Serial.print(isnan(sysSettings.zAxisUpperLimit) ? " ": String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); + Serial.println(" "); + + + return STATUS_OK; + } + + if(gcodeLine.substring(0, 3) == "B18"){ + //The B18 sets the current Z position as Lower Limit for zAxis + + sysSettings.zAxisLowerLimit = zAxis.read(); + settingsSaveToEEprom(); + + Serial.print("Lower limit set to: "); + Serial.print(isnan(sysSettings.zAxisLowerLimit) ? " ": String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); + Serial.println(" "); + + return STATUS_OK; + } + if(gcodeLine.substring(0, 3) == "B19"){ + //The B19 clears limits for zAxis + + sysSettings.zAxisUpperLimit = NAN; + sysSettings.zAxisLowerLimit = NAN; + settingsSaveToEEprom(); + + Serial.println(F("Z Axis Limits Cleared")); + + + return STATUS_OK; + } + if(gcodeLine.substring(0, 3) == "B20"){ + //The B19 echoes limits for zAxis + + Serial.print(F("Z Axis Upper Limit: ")); + Serial.print(isnan(sysSettings.zAxisUpperLimit) ? String(" ") : String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); + Serial.print(F(" Lower Limit: ")); + Serial.print(isnan(sysSettings.zAxisLowerLimit) ? String(" "): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); + Serial.println(" "); + + return STATUS_OK; + } + // Use 'B99 ON' to set FAKE_SERVO mode on, // 'B99' with no parameter, or any parameter other than 'ON' // turns FAKE_SERVO mode off. @@ -839,7 +889,7 @@ void G10(const String& readString){ zAxis.set(zgoto); zAxis.endMove(zgoto); - zAxis.attach(); + zAxis.attach(); } void G38(const String& readString) { diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index 065a016a..53dcce66 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -105,6 +105,8 @@ void settingsReset() { sysSettings.leftChainTolerance = 0.0; // float leftChainTolerance; sysSettings.rightChainTolerance = 0.0; // float rightChainTolerance; sysSettings.positionErrorLimit = 2.0; // float positionErrorLimit; + sysSettings.zAxisUpperLimit = NAN; // float zAxisUpperLimit + sysSettings.zAxisLowerLimit = NAN; // float zAxisLowerLimit sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; } diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index cd18150b..9077eea9 100644 --- a/cnc_ctrl_v1/Settings.h +++ b/cnc_ctrl_v1/Settings.h @@ -81,6 +81,8 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre float leftChainTolerance; float rightChainTolerance; float positionErrorLimit; + float zAxisUpperLimit; // a safety feature to prevent motors from atempting to move the z axis beyong a user specified constraint. + float zAxisLowerLimit; byte eepromValidData; // This should always be last, that way if an error // happens in writing, it will not be written and we } settings_t; // will know to reset the settings diff --git a/pull_request_template.md b/pull_request_template.md index f3ccccb1..d55bd7de 100644 --- a/pull_request_template.md +++ b/pull_request_template.md @@ -5,13 +5,56 @@ Please let the community know some basic information about this pull request. ## What does this pull request do? Does it add a new feature or fix a bug? +This is a new feature. I have made some small tweaks to the code to be able to set upper and lower limits for the z axis in order to prevent motors from forcing the Z Axis beyond its limits. + +I have added two variables to settings +float zAxisUpperLimit +float zAxisLowerLimit + +I have created 4 "B" commands +B17 Sets the z axis upper limit to the current z axis position +B18 Sets the z axis lower limit to the current z axis position +B19 Clears z axis limits +B20 Echoes back z axis limits + ## Does this firmware change affect kinematics or any part of the calibration process? + +It does not affect Kinematics. And I have kept it apart from calibration as some users might want to adjust this on the fly as part of the regular use. + ### a) If so, does this change require recalibration? + +It does not require recalibration. However if the user wishes to establish some limits, he/she must set the limits using gcode commands B17 (Upper) and B18 (Lower) + ### b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible. + +By default this limits are set to NAN and will be ignored until specified. + ### c) Has the calibration model in gc/hc/wc been updated to agree with firmware change? + +No recalibration needed. I intend to update webcontrol to be able to set the limits within the user interface. Meanwhile to make use of it you can send gcode directly. + ### d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)? +It has been tested on an actual machine only + ## How can this pull request be tested? Please provide detailed steps about how to test this pull request. +1 - Move the Z axis to the highest point you with to set as a limit. +2 - Send a B17 gcode command. +3 - Move the Z axis to the lowest point you with to set as a limit. +4 - Send a B18 gcode command. +5 - Now attempt to move the Z axis beyond those limits. It should prevent you from exceeding the limits. +6 - Send the B20 gcode command and observe the limits echoed back +7 - Now attempt to reset the 0 location for the z axis +8 - Send the B20 gcode command and observe the limits echoed back, they should have been updated to account for the new 0 location +9 - Send the B19 gcode command to erase the limits +10 - Send the B20 gcode command and observe the limits echoes back, the should have been cleared. +11 - Now attempt to move the Z axis beyond the limits set in steps 1 and 2. It should allow you to move freely. (Careful not to exceed the physical limits of your machine) + Thanks for contributing! + + + + + From 71d5cc914166ace67c305a95d938db5f57d17dca Mon Sep 17 00:00:00 2001 From: Ramon Arias Date: Tue, 19 May 2020 17:33:54 -0500 Subject: [PATCH 08/14] Changes requested Made changes per requests during review --- cnc_ctrl_v1/Axis.cpp | 26 +- cnc_ctrl_v1/GCode.cpp | 80 ++-- cnc_ctrl_v1/Settings.cpp | 6 + cnc_ctrl_v1/Settings.h | 2 +- pull_request_template.md | 997 +++++++++++++++++++++++++++++++++++++-- 5 files changed, 1025 insertions(+), 86 deletions(-) diff --git a/cnc_ctrl_v1/Axis.cpp b/cnc_ctrl_v1/Axis.cpp index 514712a4..4e1127ca 100644 --- a/cnc_ctrl_v1/Axis.cpp +++ b/cnc_ctrl_v1/Axis.cpp @@ -45,14 +45,16 @@ void Axis::initializePID(const unsigned long& loopInterval){ void Axis::write(const float& targetPosition){ - // Check that the Z axis position is withing limits stecified in Settings + _timeLastMoved = millis(); + // Check that the Z axis position is within limits specified in Settings + if(_axisName == 'Z'){ if(!isnan(sysSettings.zAxisUpperLimit) && targetPosition > sysSettings.zAxisUpperLimit){ _pidSetpoint = sysSettings.zAxisUpperLimit/ *_mmPerRotation; return; } - + if(!isnan(sysSettings.zAxisLowerLimit) && targetPosition < sysSettings.zAxisLowerLimit){ _pidSetpoint = sysSettings.zAxisLowerLimit/ *_mmPerRotation; return; @@ -60,7 +62,6 @@ void Axis::write(const float& targetPosition){ } // update target position - _timeLastMoved = millis(); _pidSetpoint = targetPosition/ *_mmPerRotation; return; } @@ -79,7 +80,7 @@ float Axis::setpoint(){ void Axis::set(const float& newAxisPosition){ // update the zAxis upper and lower limits relative to the new axis position - + if(_axisName == 'Z'){ if(!isnan(sysSettings.zAxisUpperLimit)){ sysSettings.zAxisUpperLimit += newAxisPosition - read(); @@ -88,18 +89,15 @@ void Axis::set(const float& newAxisPosition){ if(!isnan(sysSettings.zAxisLowerLimit)){ sysSettings.zAxisLowerLimit += newAxisPosition - read(); } - + if(!isnan(sysSettings.zAxisUpperLimit) || !isnan(sysSettings.zAxisLowerLimit)){ settingsSaveToEEprom(); } } - + //reset everything to the new value _pidSetpoint = newAxisPosition/ *_mmPerRotation; - motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); - - - + motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation); } long Axis::steps(){ @@ -259,8 +257,9 @@ void Axis::detachIfIdle(){ void Axis::endMove(const float& finalTarget){ - - // Check that the Z axis position is withing limits stecified in Settings + _timeLastMoved = millis(); + + // Check that the Z axis position is within limits specified in Settings if(_axisName == 'Z'){ if(!isnan(sysSettings.zAxisUpperLimit) && finalTarget > sysSettings.zAxisUpperLimit){ @@ -274,8 +273,7 @@ void Axis::endMove(const float& finalTarget){ } } - _timeLastMoved = millis(); - _pidSetpoint = finalTarget/ *_mmPerRotation; + _pidSetpoint = finalTarget/ *_mmPerRotation; } diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index f1198efc..4d5e072d 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -373,51 +373,63 @@ byte executeBcodeLine(const String& gcodeLine){ if(gcodeLine.substring(0, 3) == "B17"){ //The B17 sets the current Z position as Upper Limit for zAxis - sysSettings.zAxisUpperLimit = zAxis.read(); - settingsSaveToEEprom(); + if(!isnan(zAxis.read())){ - Serial.print("Upper limit set to: "); - Serial.print(isnan(sysSettings.zAxisUpperLimit) ? " ": String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); - Serial.println(" "); - + settingsStoreGlobalSetting(byte(43), zAxis.read()); + + Serial.print(F("Upper limit set to: ")); + Serial.println(isnan(sysSettings.zAxisUpperLimit) ? F(" "): String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); - return STATUS_OK; + return STATUS_OK; + + } else { + + Serial.println(F("Error setting limit")); + + return STATUS_GCODE_INVALID_TARGET; + + } } - if(gcodeLine.substring(0, 3) == "B18"){ - //The B18 sets the current Z position as Lower Limit for zAxis + if(gcodeLine.substring(0, 3) == "B18"){ + //The B18 sets the current Z position as Lower Limit for zAxis - sysSettings.zAxisLowerLimit = zAxis.read(); - settingsSaveToEEprom(); + if(!isnan(zAxis.read())){ + settingsStoreGlobalSetting(byte(44), zAxis.read()); - Serial.print("Lower limit set to: "); - Serial.print(isnan(sysSettings.zAxisLowerLimit) ? " ": String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - Serial.println(" "); + Serial.print(F("Lower limit set to: ")); + Serial.println(isnan(sysSettings.zAxisLowerLimit) ? F(" "): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - return STATUS_OK; - } - if(gcodeLine.substring(0, 3) == "B19"){ - //The B19 clears limits for zAxis + return STATUS_OK; - sysSettings.zAxisUpperLimit = NAN; - sysSettings.zAxisLowerLimit = NAN; - settingsSaveToEEprom(); + } else { - Serial.println(F("Z Axis Limits Cleared")); - - - return STATUS_OK; + Serial.println(F("Error setting limit")); + + return STATUS_GCODE_INVALID_TARGET; + + } } - if(gcodeLine.substring(0, 3) == "B20"){ - //The B19 echoes limits for zAxis + if(gcodeLine.substring(0, 3) == "B19"){ + //The B19 clears limits for zAxis - Serial.print(F("Z Axis Upper Limit: ")); - Serial.print(isnan(sysSettings.zAxisUpperLimit) ? String(" ") : String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); - Serial.print(F(" Lower Limit: ")); - Serial.print(isnan(sysSettings.zAxisLowerLimit) ? String(" "): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - Serial.println(" "); + settingsStoreGlobalSetting(byte(43), NAN); + settingsStoreGlobalSetting(byte(44), NAN); + + + Serial.println(F("Z Axis Limits Cleared")); + + return STATUS_OK; + } + if(gcodeLine.substring(0, 3) == "B20"){ + //The B20 echoes limits for zAxis + + Serial.print(F("Z Axis Upper Limit: ")); + Serial.print(isnan(sysSettings.zAxisUpperLimit) ? F("NAN") : String(sysSettings.zAxisUpperLimit / sys.inchesToMMConversion)); + Serial.print(F(" Lower Limit: ")); + Serial.println(isnan(sysSettings.zAxisLowerLimit) ? F("NAN"): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion)); - return STATUS_OK; + return STATUS_OK; } // Use 'B99 ON' to set FAKE_SERVO mode on, @@ -889,7 +901,7 @@ void G10(const String& readString){ zAxis.set(zgoto); zAxis.endMove(zgoto); - zAxis.attach(); + zAxis.attach(); } void G38(const String& readString) { diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index 53dcce66..b695fb61 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -412,6 +412,12 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ case 42: sysSettings.positionErrorLimit = value; break; + case 43: + sysSettings.zAxisUpperLimit = value; + break; + case 44: + sysSettings.zAxisLowerLimit = value; + break; default: return(STATUS_INVALID_STATEMENT); } diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index 9077eea9..503e4961 100644 --- a/cnc_ctrl_v1/Settings.h +++ b/cnc_ctrl_v1/Settings.h @@ -81,7 +81,7 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre float leftChainTolerance; float rightChainTolerance; float positionErrorLimit; - float zAxisUpperLimit; // a safety feature to prevent motors from atempting to move the z axis beyong a user specified constraint. + float zAxisUpperLimit; // A safety feature to prevent motors from attempting to move the z axis beyong a user specified constraint. float zAxisLowerLimit; byte eepromValidData; // This should always be last, that way if an error // happens in writing, it will not be written and we diff --git a/pull_request_template.md b/pull_request_template.md index d55bd7de..61bd2952 100644 --- a/pull_request_template.md +++ b/pull_request_template.md @@ -1,60 +1,983 @@ -Thanks for contributing to The Maslow Firmware! You rock. -Please let the community know some basic information about this pull request. -## What does this pull request do? -Does it add a new feature or fix a bug? -This is a new feature. I have made some small tweaks to the code to be able to set upper and lower limits for the z axis in order to prevent motors from forcing the Z Axis beyond its limits. -I have added two variables to settings -float zAxisUpperLimit -float zAxisLowerLimit -I have created 4 "B" commands -B17 Sets the z axis upper limit to the current z axis position -B18 Sets the z axis lower limit to the current z axis position -B19 Clears z axis limits -B20 Echoes back z axis limits + + + + + + + + + + + -## Does this firmware change affect kinematics or any part of the calibration process? -It does not affect Kinematics. And I have kept it apart from calibration as some users might want to adjust this on the fly as part of the regular use. -### a) If so, does this change require recalibration? + + + + + + + -It does not require recalibration. However if the user wishes to establish some limits, he/she must set the limits using gcode commands B17 (Upper) and B18 (Lower) -### b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible. + + + Firmware/pull_request_template.md at master · MaslowCNC/Firmware · GitHub + + + + -By default this limits are set to NAN and will be ignored until specified. + + -### c) Has the calibration model in gc/hc/wc been updated to agree with firmware change? + + -No recalibration needed. I intend to update webcontrol to be able to set the limits within the user interface. Meanwhile to make use of it you can send gcode directly. + -### d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)? -It has been tested on an actual machine only -## How can this pull request be tested? -Please provide detailed steps about how to test this pull request. + -1 - Move the Z axis to the highest point you with to set as a limit. -2 - Send a B17 gcode command. -3 - Move the Z axis to the lowest point you with to set as a limit. -4 - Send a B18 gcode command. -5 - Now attempt to move the Z axis beyond those limits. It should prevent you from exceeding the limits. -6 - Send the B20 gcode command and observe the limits echoed back -7 - Now attempt to reset the 0 location for the z axis -8 - Send the B20 gcode command and observe the limits echoed back, they should have been updated to account for the new 0 location -9 - Send the B19 gcode command to erase the limits -10 - Send the B20 gcode command and observe the limits echoes back, the should have been cleared. -11 - Now attempt to move the Z axis beyond the limits set in steps 1 and 2. It should allow you to move freely. (Careful not to exceed the physical limits of your machine) + -Thanks for contributing! + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ Skip to content + + + + + + + + + + + +
+ +
+ + + + +
+ + + +
+ + + + + + + + + +
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
+
+ + + + + + + + Permalink + + + + + +
+ + +
+ + Branch: + master + + + + +
+ + + +
+
+
+ +
+ + Find file + + + Copy path + +
+
+ + +
+ + Find file + + + Copy path + +
+
+ + + + +
+
+ + @BarbourSmith + BarbourSmith + + Update wording + + + + 72014b7 + Aug 14, 2019 + +
+ +
+
+ + 1 contributor + + +
+ +

+ Users who have contributed to this file +

+
+ +
+
+
+
+ + + + + + +
+ +
+
+ + 17 lines (12 sloc) + + 819 Bytes +
+ +
+ +
+ Raw + Blame + History +
+ + +
+ + + + + + +
+
+
+ + + + +
+

Thanks for contributing to The Maslow Firmware! You rock.

+

Please let the community know some basic information about this pull request.

+

What does this pull request do?

+

Does it add a new feature or fix a bug?

+

Does this firmware change affect kinematics or any part of the calibration process?

+

a) If so, does this change require recalibration?

+

b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible.

+

c) Has the calibration model in gc/hc/wc been updated to agree with firmware change?

+

d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)?

+

How can this pull request be tested?

+

Please provide detailed steps about how to test this pull request.

+

Thanks for contributing!

+
+
+ +
+ + + +
+ + +
+ + +
+
+ + + + + +
+
+ +
+
+ + +
+ + + + + + +
+ + + You can’t perform that action at this time. +
+ + + + + + + + + + + + + + + + + + + + + From 91eefe007ab81a01812d69b288bf5422ea0b6e2f Mon Sep 17 00:00:00 2001 From: BarbourSmith Date: Wed, 20 May 2020 16:28:55 -0700 Subject: [PATCH 09/14] Revert pull pull request template to original version --- pull_request_template.md | 990 +-------------------------------------- 1 file changed, 12 insertions(+), 978 deletions(-) diff --git a/pull_request_template.md b/pull_request_template.md index 61bd2952..f3ccccb1 100644 --- a/pull_request_template.md +++ b/pull_request_template.md @@ -1,983 +1,17 @@ +Thanks for contributing to The Maslow Firmware! You rock. +Please let the community know some basic information about this pull request. +## What does this pull request do? +Does it add a new feature or fix a bug? +## Does this firmware change affect kinematics or any part of the calibration process? +### a) If so, does this change require recalibration? +### b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible. +### c) Has the calibration model in gc/hc/wc been updated to agree with firmware change? +### d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)? +## How can this pull request be tested? +Please provide detailed steps about how to test this pull request. - - - - - - - - - - - - - - - - - - - - - - - - - - Firmware/pull_request_template.md at master · MaslowCNC/Firmware · GitHub - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- Skip to content - - - - - - - - - - - -
- -
- - - - -
- - - -
- - - - - - - - - -
-
-
- - - - - - - - - - - - - - - - - - - - - - - - -
-
- - - - - - - - Permalink - - - - - -
- - -
- - Branch: - master - - - - -
- - - -
-
-
- -
- - Find file - - - Copy path - -
-
- - -
- - Find file - - - Copy path - -
-
- - - - -
-
- - @BarbourSmith - BarbourSmith - - Update wording - - - - 72014b7 - Aug 14, 2019 - -
- -
-
- - 1 contributor - - -
- -

- Users who have contributed to this file -

-
- -
-
-
-
- - - - - - -
- -
-
- - 17 lines (12 sloc) - - 819 Bytes -
- -
- -
- Raw - Blame - History -
- - -
- - - - - - -
-
-
- - - - -
-

Thanks for contributing to The Maslow Firmware! You rock.

-

Please let the community know some basic information about this pull request.

-

What does this pull request do?

-

Does it add a new feature or fix a bug?

-

Does this firmware change affect kinematics or any part of the calibration process?

-

a) If so, does this change require recalibration?

-

b) If so, is there an option for user to opt-out of the change until ready for recalibration? If not, explain why this is not possible.

-

c) Has the calibration model in gc/hc/wc been updated to agree with firmware change?

-

d) Has this PR been tested on actual machine and/or in fake servo mode (indicate which or both)?

-

How can this pull request be tested?

-

Please provide detailed steps about how to test this pull request.

-

Thanks for contributing!

-
-
- -
- - - -
- - -
- - -
-
- - - - - -
-
- -
-
- - -
- - - - - - -
- - - You can’t perform that action at this time. -
- - - - - - - - - - - - - - - - - - - - - - +Thanks for contributing! From d9cfdddda1ab117a3b0ebda5827a6c691f49fd4f Mon Sep 17 00:00:00 2001 From: KRKeegan Date: Wed, 5 Aug 2020 16:39:48 -0700 Subject: [PATCH 10/14] Fix Missed Conflict --- cnc_ctrl_v1/Config.h | 7 ------- 1 file changed, 7 deletions(-) diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index a9d70b89..668d76f9 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -26,17 +26,10 @@ #define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging #define FAKE_SERVO_PERMITTED 42 // store this value -<<<<<<< HEAD #define FAKE_SERVO 4095 // store the state of FAKE_SERVO in EEPROM[ 4095 ] to preserve // the state of FAKE_SERVO mode over resets. // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', // 'B99' with no parameter, or any parameter other than 'ON' -======= -#define FAKE_SERVO 4095 // in EEPROM[ 4095 ] to preserve - // the state of FAKE_SERVO mode over resets. - // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', - // 'B99' with no parameter, or any parameter other than 'ON' ->>>>>>> maslow/master // puts a '0' in that location and turns FAKE_SERVO mode off. // Useful for testing on an arduino only (e.g. without motors). From ce31649a5df120b80535508fe2527e9f45a3d8fe Mon Sep 17 00:00:00 2001 From: KRKeegan Date: Wed, 5 Aug 2020 16:42:04 -0700 Subject: [PATCH 11/14] Fix Duplicate Init from Merge --- cnc_ctrl_v1/cnc_ctrl_v1.ino | 3 --- 1 file changed, 3 deletions(-) diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index d349e786..4b171177 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -49,9 +49,6 @@ byte systemRtExecAlarm; // Define global flag for FAKE_SERVO state int FAKE_SERVO_STATE = 0; -// Define global flag for FAKE_SERVO state -int FAKE_SERVO_STATE = 0; - // Define axes, it might be tighter to define these within the sys struct Axis leftAxis; Axis rightAxis; From 35cce7d99c75517e2593cd383824480a468851a2 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Wed, 9 Sep 2020 13:18:24 -0500 Subject: [PATCH 12/14] Spindle pwm pin 45 added Added $60 min speed and $61 spindle max speed for pwm output Added S functionality to set spindle speed. pwm setting is scaled from 0 to max with min being set as the start speed. --- cnc_ctrl_v1/Config.h | 9 +++++++ cnc_ctrl_v1/GCode.cpp | 17 ++++++++++++ cnc_ctrl_v1/GCode.h | 1 + cnc_ctrl_v1/Settings.cpp | 6 +++++ cnc_ctrl_v1/Settings.h | 6 ++++- cnc_ctrl_v1/Spindle.cpp | 58 +++++++++++++++++++++++++++++++++++++++- cnc_ctrl_v1/Spindle.h | 11 ++++++++ cnc_ctrl_v1/System.cpp | 7 +++++ cnc_ctrl_v1/System.h | 1 + 9 files changed, 114 insertions(+), 2 deletions(-) diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index 668d76f9..ce14e8b3 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -20,12 +20,17 @@ // Debugging Options #define verboseDebug 0 // set to 0 for no debug messages, 1 for single-line messages, 2 to also output ring buffer contents + #define misloopDebug 0 // set to 1 for a warning every time the movement loop fails // to complete before being interrupted, helpful for loop // LOOPINTERVAL tuning + #define KINEMATICSDBG 0 // set to 1 for additional kinematics debug messaging +#define SPINDLE_SPEED 1 // set to 1 for pwm spindle speed control + #define FAKE_SERVO_PERMITTED 42 // store this value + #define FAKE_SERVO 4095 // store the state of FAKE_SERVO in EEPROM[ 4095 ] to preserve // the state of FAKE_SERVO mode over resets. // Use 'B99 ON' to turn FAKE_SERVO mode on and set EEPROM[ 4095 ] to '1', @@ -55,12 +60,15 @@ // Serial variables #define INCBUFFERLENGTH 128 // The number of bytes(characters) allocated to the // incoming buffer. + #define EXPGCODELINE 60 // Maximum expected Gcode line length in characters // including line ending character(s). Assumes // client will not send more than this. Ground // Control is currently set to 60. NIST spec allows // 256. This value must be <= INCBUFFERLENGTH + #define MAXBUFFERLINES 4 // The maximum number of lines allowed in the buffer + #define POSITIONTIMEOUT 200 // The minimum number of milliseconds between // position reports sent to Ground Control. This // cannot be larger than the connection timout in @@ -72,6 +80,7 @@ #define CMD_RESET 0x18 // ctrl-x., if received the program should do a soft reset // if received the program should do a soft reset + #define CMD_RESET2 '`' // alternate char because GC won't use control characters in a macro #endif diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index 19017669..338d4344 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -398,7 +398,17 @@ byte executeBcodeLine(const String& gcodeLine){ } return STATUS_INVALID_STATEMENT; } +void executeScodeLine(const String& gcodeLine){ + /* executes a single line of gcode beginning with the character 'S' for spindle speed */ + int sNumber = extractGcodeValue(gcodeLine,'S',-1); + if (sNumber == -1){ + sNumber = sys.SpindleSpeed; + } + if (setSpindleSpeed(sNumber)){ + sys.SpindleSpeed = sNumber; + } +} void executeGcodeLine(const String& gcodeLine){ /* @@ -660,6 +670,13 @@ byte interpretCommandString(String& cmdString){ Serial.println(gcodeLine); executeMcodeLine(gcodeLine); } + else if(gcodeLine[0] == 'S'){ + #if defined (verboseDebug) && verboseDebug > 0 + Serial.print(F("iCS executing S code: ")); + #endif + Serial.println(gcodeLine); + executeScodeLine(gcodeLine); + } else { #if defined (verboseDebug) && verboseDebug > 0 Serial.print(F("iCS executing G code: ")); diff --git a/cnc_ctrl_v1/GCode.h b/cnc_ctrl_v1/GCode.h index 880a601d..08c037c4 100644 --- a/cnc_ctrl_v1/GCode.h +++ b/cnc_ctrl_v1/GCode.h @@ -34,6 +34,7 @@ float extractGcodeValue(const String&, char, const float&); byte executeBcodeLine(const String&); void executeGcodeLine(const String&); void executeMcodeLine(const String&); +void executeScodeLine(const String&); void executeOtherCodeLine(const String&); int findNextGM(const String&, const int&); void sanitizeCommandString(String&); diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index c92fd9b3..5b60c0b4 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -109,6 +109,8 @@ void settingsReset() { sysSettings.reserved2 = 0.0; sysSettings.chainElongationFactor = 8.1E-6; // m/m/N sysSettings.sledWeight = 11.6*9.8; // Newtons. For a sled with one ring kit, one Rigid 2200 router and two 2.35kg bricks on a 5/8" thick mdf 18" diameter base. + sysSettings.spindleMin = 4000; + sysSettings.spindleMax = 24000; sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; } @@ -429,6 +431,10 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ sysSettings.sledWeight = value; kinematics.init();; break; + case 60: + sysSettings.spindleMin = value; + case 61: + sysSettings.spindleMax = value; default: return(STATUS_INVALID_STATEMENT); } diff --git a/cnc_ctrl_v1/Settings.h b/cnc_ctrl_v1/Settings.h index 29fb3944..be792b35 100644 --- a/cnc_ctrl_v1/Settings.h +++ b/cnc_ctrl_v1/Settings.h @@ -36,7 +36,9 @@ enum SpindleAutomationType { NONE, SERVO, RELAY_ACTIVE_HIGH, - RELAY_ACTIVE_LOW }; + RELAY_ACTIVE_LOW, + SPEED_CONTROL_RELAY_ACTIVE_HIGH, + SPEED_CONTROL_RELAY_ACTIVE_LOW}; typedef struct { // I think this is about ~128 bytes in size if I counted correctly float machineWidth; @@ -85,6 +87,8 @@ typedef struct { // I think this is about ~128 bytes in size if I counted corre float reserved2; float chainElongationFactor; // m/m/N. This is the ratio of chain length increase due to chain tension. typically 8x10E-6; // m/m/N float sledWeight; // Newtons. simply multiply kg by 9.8 or pounds by 2.2*9.8 + int spindleMin; //added for pwm spindle control + int spindleMax; //added for pwm spindle control byte eepromValidData; // This should always be last, that way if an error // happens in writing, it will not be written and we } settings_t; // will know to reset the settings diff --git a/cnc_ctrl_v1/Spindle.cpp b/cnc_ctrl_v1/Spindle.cpp index 853a1d64..c7b2c0f0 100644 --- a/cnc_ctrl_v1/Spindle.cpp +++ b/cnc_ctrl_v1/Spindle.cpp @@ -20,7 +20,9 @@ // the variables SpindlePowerControlPin and LaserPowerPin are assigned in setupAxes() in System.cpp // Globals for Spindle control, both poorly named +#ifndef SPINDLE_SPEED Servo myservo; // create servo object to control a servo +#endif void setSpindlePower(bool powerState) { /* @@ -41,6 +43,7 @@ void setSpindlePower(bool powerState) { Serial.print(F("Spindle automation type ")); Serial.print(spindleAutomateType); #endif + #ifndef SPINDLE_SPEED if (spindleAutomateType == SERVO) { // use a servo to control a standard wall switch #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F(" with servo (idle=")); @@ -70,7 +73,42 @@ void setSpindlePower(bool powerState) { if(sys.stop){return;} myservo.detach(); // stop servo control } - else if (spindleAutomateType == RELAY_ACTIVE_HIGH) { + #endif + if (spindleAutomateType == SPEED_CONTROL_RELAY_ACTIVE_HIGH){ + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F(" as digital power and pwm speed control, active high")); + #endif + pinMode(SpindlePowerControlPin, OUTPUT); + if (powerState) { // turn on spindle + Serial.println(F("Turning Spindle On")); + digitalWrite(SpindlePowerControlPin, HIGH); + Serial.println(F("Adjusting Spindle Speed to Minimum")); + setSpindleSpeed(sysSettings.spindleMin); + } + else { // turn off spindle + Serial.println(F("Turning Spindle Off")); + digitalWrite(SpindlePowerControlPin, LOW); + digitalWrite(SpindleSpeedControlPin, LOW); + } + } + if (spindleAutomateType == SPEED_CONTROL_RELAY_ACTIVE_LOW){ + #if defined (verboseDebug) && verboseDebug > 1 + Serial.print(F(" as digital power and pwm speed control, active low")); + #endif + pinMode(SpindlePowerControlPin, OUTPUT); + if (powerState) { // turn on spindle + Serial.println(F("Turning Spindle On")); + digitalWrite(SpindlePowerControlPin, LOW); + Serial.println(F("Adjusting Spindle Speed to Minimum")); + setSpindleSpeed(sysSettings.spindleMin); + } + else { // turn off spindle + Serial.println(F("Turning Spindle Off")); + digitalWrite(SpindlePowerControlPin, HIGH); + digitalWrite(SpindleSpeedControlPin, LOW); + } + } + if (spindleAutomateType == RELAY_ACTIVE_HIGH) { #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F(" as digital output, active high")); #endif @@ -103,6 +141,24 @@ void setSpindlePower(bool powerState) { } } +int setSpindleSpeed(int spindleSpeed){ + // map 0-255 min spindle speed to max spindle speed + // output 0-255 + if (spindleSpeed < sysSettings.spindleMin){ + spindleSpeed = sysSettings.spindleMin; + } + if (spindleSpeed > sysSettings.spindleMax){ + spindleSpeed = sysSettings.spindleMax; + } + long spd = map (spindleSpeed, 0, sysSettings.spindleMax, 0, 255); + analogWrite(SpindleSpeedControlPin,spd); + return(1); + //for (i=0;i 0) pinMode(aux3,INPUT); if (aux5 > 0) pinMode(aux5,INPUT); if (aux6 > 0) pinMode(aux6,INPUT); + #ifndef SPINDLE_SPEED if (aux7 > 0) pinMode(aux7,INPUT); + #endif if (aux8 > 0) pinMode(aux8,INPUT); if (aux9 > 0) pinMode(aux9,INPUT); } diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index 25bea189..3f0d88b7 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -60,6 +60,7 @@ typedef struct { bool useRelativeUnits; // unsigned long lastSerialRcvd; // The millis of the last rcvd serial command, used by watchdo int lastGCommand; //Stores the value of the last command run eg: G01 -> 1 + int SpindleSpeed; // store the current spindle speed -> 4000 int lastTool; //Stores the value of the last tool number eg: T4 -> 4 int nextTool; //Stores the value of the next tool number eg: T4 -> 4 float inchesToMMConversion; //Used to track whether to convert from inches, can probably be done in a way that doesn't require RAM From 1811d70eb6b7d8b8ee083f89881dc7e5f0fee162 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Sat, 12 Sep 2020 21:55:12 -0500 Subject: [PATCH 13/14] Update Settings.cpp default is for pwm pin to be active and for relay to be active high --- cnc_ctrl_v1/Settings.cpp | 15 ++------------- 1 file changed, 2 insertions(+), 13 deletions(-) diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index fd66cf22..c5dada18 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -79,7 +79,7 @@ void settingsReset() { sysSettings.distPerRot = 63.5; // float distPerRot; sysSettings.maxFeed = 700; // int maxFeed; sysSettings.zAxisAttached = true; // zAxisAttached; - sysSettings.spindleAutomateType = NONE; // bool spindleAutomate; + sysSettings.spindleAutomateType = SPEED_CONTROL_RELAY_ACTIVE_HIGH; // bool spindleAutomate; sysSettings.maxZRPM = 12.60; // float maxZRPM; sysSettings.zDistPerRot = 3.17; // float zDistPerRot; sysSettings.zEncoderSteps = 7560.0; // float zEncoderSteps; @@ -111,8 +111,6 @@ void settingsReset() { sysSettings.sledWeight = 11.6*9.8; // Newtons. For a sled with one ring kit, one Rigid 2200 router and two 2.35kg bricks on a 5/8" thick mdf 18" diameter base. sysSettings.spindleMin = 4000; sysSettings.spindleMax = 24000; - sysSettings.zAxisUpperLimit = NAN; // float zAxisUpperLimit - sysSettings.zAxisLowerLimit = NAN; // float zAxisLowerLimit sysSettings.eepromValidData = EEPROMVALIDDATA; // byte eepromValidData; } @@ -390,7 +388,6 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 37: sysSettings.chainSagCorrection = value; - kinematics.init(); break; case 38: settingsSaveStepstoEEprom(); @@ -434,18 +431,10 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ sysSettings.sledWeight = value; kinematics.init();; break; - case 47: - sysSettings.zAxisUpperLimit = value; - break; - case 48: - sysSettings.zAxisLowerLimit = value; - break; case 60: sysSettings.spindleMin = value; - break; case 61: - sysSettings.spindleMax = value; - break; + sysSettings.spindleMax = value; default: return(STATUS_INVALID_STATEMENT); } From c073f522bd243ee08181804e0f71df0cdddb7dc6 Mon Sep 17 00:00:00 2001 From: Orob-Maslow <59507087+Orob-Maslow@users.noreply.github.com> Date: Sun, 13 Sep 2020 18:01:37 -0500 Subject: [PATCH 14/14] Update System.cpp --- cnc_ctrl_v1/System.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index b088cf60..3612c352 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -375,7 +375,7 @@ void setupAxes(){ if (aux5 > 0) pinMode(aux5,INPUT); if (aux6 > 0) pinMode(aux6,INPUT); #ifndef SPINDLE_SPEED - if (aux7 > 0) pinMode(aux7,INPUT); + if (aux7 > 0) pinMode(aux7,INPUT); #endif if (aux8 > 0) pinMode(aux8,INPUT); if (aux9 > 0) pinMode(aux9,INPUT);