diff --git a/Robot.md b/Robot.md new file mode 100644 index 00000000..5cffd8b1 --- /dev/null +++ b/Robot.md @@ -0,0 +1,4 @@ +ModerationLevel = communityManaged + + Facilitator: barboursmith + diff --git a/cnc_ctrl_v1/GCode.cpp b/cnc_ctrl_v1/GCode.cpp index e2b0ed7a..07f14acc 100644 --- a/cnc_ctrl_v1/GCode.cpp +++ b/cnc_ctrl_v1/GCode.cpp @@ -23,7 +23,7 @@ Copyright 2014-2017 Bar Smith*/ RingBuffer incSerialBuffer; String readyCommandString = ""; //KRK why is this a global? String gcodeLine = ""; //Our use of this is a bit sloppy, at times, - //we pass references to this global and then + //we pass references to this global and then //name them the same thing. void initGCode(){ @@ -34,13 +34,13 @@ void initGCode(){ void readSerialCommands(){ /* - Check to see if a new character is available from the serial connection, + Check to see if a new character is available from the serial connection, if this is a necessary character write to the incSerialBuffer otherwise discard it. */ - + static bool quickCommandFlag = false; - + if (Serial.available() > 0) { while (Serial.available() > 0) { char c = Serial.read(); @@ -68,10 +68,10 @@ void readSerialCommands(){ } if (sys.stop){return;} } - #if defined (verboseDebug) && verboseDebug > 1 + #if defined (verboseDebug) && verboseDebug > 1 // print ring buffer contents Serial.println(F("rSC added to ring buffer")); - incSerialBuffer.print(); + incSerialBuffer.print(); #endif } } @@ -79,9 +79,9 @@ void readSerialCommands(){ int findEndOfNumber(const String& textString, const int& index){ //Return the index of the last digit of the number beginning at the index passed in unsigned int i = index; - + while (i < textString.length()){ - + if(isDigit(textString[i]) or isPunct(textString[i])){ //If we're still looking at a number, keep goin i++; } @@ -101,51 +101,51 @@ float extractGcodeValue(const String& readString, char target, const float& defa int end; String numberAsString; float numberAsFloat; - + begin = readString.indexOf(target); end = findEndOfNumber(readString,begin+1); numberAsString = readString.substring(begin+1,end); - + numberAsFloat = numberAsString.toFloat(); - + if (begin == -1){ //if the character was not found, return error return defaultReturn; } - + return numberAsFloat; } byte executeBcodeLine(const String& gcodeLine){ /* - + Executes a single line of gcode beginning with the character 'B'. - + */ - + //Handle B-codes - + if(gcodeLine.substring(0, 3) == "B05"){ Serial.print(F("Firmware Version ")); Serial.println(VERSIONNUMBER); return STATUS_OK; } - + if(sys.state == STATE_OLD_SETTINGS){ return STATUS_OLD_SETTINGS; } - + if(gcodeLine.substring(0, 3) == "B01"){ - + Serial.println(F("Motor Calibration Not Needed")); - + return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B02"){ calibrateChainLengths(gcodeLine); return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B04"){ //set flag to ignore position error limit during the tests sys.state = (sys.state | STATE_POS_ERR_IGNORE); @@ -169,50 +169,50 @@ byte executeBcodeLine(const String& gcodeLine){ sys.state = (sys.state & (!STATE_POS_ERR_IGNORE)); return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B06"){ Serial.println(F("Setting Chain Lengths To: ")); float newL = extractGcodeValue(gcodeLine, 'L', 0); float newR = extractGcodeValue(gcodeLine, 'R', 0); - + leftAxis.set(newL); rightAxis.set(newR); - + Serial.print(F("Left: ")); Serial.print(leftAxis.read()); Serial.println(F("mm")); Serial.print(F("Right: ")); Serial.print(rightAxis.read()); Serial.println(F("mm")); - + return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B08"){ //Manually recalibrate chain lengths leftAxis.set(sysSettings.originalChainLength); rightAxis.set(sysSettings.originalChainLength); - + Serial.print(F("Left: ")); Serial.print(leftAxis.read()); Serial.println(F("mm")); Serial.print(F("Right: ")); Serial.print(rightAxis.read()); Serial.println(F("mm")); - + kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); - + Serial.println(F("Message: The machine chains have been manually re-calibrated.")); - + return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B09"){ //Directly command each axis to move to a given distance float lDist = extractGcodeValue(gcodeLine, 'L', 0); float rDist = extractGcodeValue(gcodeLine, 'R', 0); float speed = extractGcodeValue(gcodeLine, 'F', 800); - + if(sys.useRelativeUnits){ if(abs(lDist) > 0){ singleAxisMove(&leftAxis, leftAxis.read() + lDist, speed); @@ -225,10 +225,10 @@ byte executeBcodeLine(const String& gcodeLine){ singleAxisMove(&leftAxis, lDist, speed); singleAxisMove(&rightAxis, rDist, speed); } - + return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B10"){ //measure the left axis chain length Serial.print(F("[Measure: ")); @@ -241,15 +241,15 @@ byte executeBcodeLine(const String& gcodeLine){ Serial.println(F("]")); return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B11"){ //run right motor in the given direction at the given speed for the given time float speed = extractGcodeValue(gcodeLine, 'S', 100); float time = extractGcodeValue(gcodeLine, 'T', 1); - + double ms = 1000*time; double begin = millis(); - + int i = 0; while (millis() - begin < ms){ if (gcodeLine.indexOf('L') != -1){ @@ -265,7 +265,7 @@ byte executeBcodeLine(const String& gcodeLine){ } return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B13"){ //PID Testing of Velocity float left = extractGcodeValue(gcodeLine, 'L', 0); @@ -274,14 +274,14 @@ byte executeBcodeLine(const String& gcodeLine){ float stop = extractGcodeValue(gcodeLine, 'F', 1); float steps = extractGcodeValue(gcodeLine, 'I', 1); float version = extractGcodeValue(gcodeLine, 'V', 1); - + Axis* axis = &rightAxis; if (left > 0) axis = &leftAxis; if (useZ > 0) axis = &zAxis; PIDTestVelocity(axis, start, stop, steps, version); return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B14"){ //PID Testing of Position float left = extractGcodeValue(gcodeLine, 'L', 0); @@ -291,65 +291,65 @@ byte executeBcodeLine(const String& gcodeLine){ float steps = extractGcodeValue(gcodeLine, 'I', 1); float stepTime = extractGcodeValue(gcodeLine, 'T', 2000); float version = extractGcodeValue(gcodeLine, 'V', 1); - + Axis* axis = &rightAxis; if (left > 0) axis = &leftAxis; if (useZ > 0) axis = &zAxis; PIDTestPosition(axis, start, stop, steps, stepTime, version); return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B16"){ //Incrementally tests voltages to see what RPMs they produce float left = extractGcodeValue(gcodeLine, 'L', 0); float useZ = extractGcodeValue(gcodeLine, 'Z', 0); float start = extractGcodeValue(gcodeLine, 'S', 1); float stop = extractGcodeValue(gcodeLine, 'F', 1); - + Axis* axis = &rightAxis; if (left > 0) axis = &leftAxis; if (useZ > 0) axis = &zAxis; voltageTest(axis, start, stop); return STATUS_OK; } - + if(gcodeLine.substring(0, 3) == "B15"){ //The B15 command moves the chains to the length which will put the sled in the center of the sheet - + //Compute chain length for position 0,0 float chainLengthAtMiddle; kinematics.inverse(0,0,&chainLengthAtMiddle,&chainLengthAtMiddle); - + //Adjust left chain length singleAxisMove(&leftAxis, chainLengthAtMiddle, 800); - + //Adjust right chain length singleAxisMove(&rightAxis, chainLengthAtMiddle, 800); - + //Reload the position kinematics.forward(leftAxis.read(), rightAxis.read(), &sys.xPosition, &sys.yPosition, 0, 0); - + return STATUS_OK; } return STATUS_INVALID_STATEMENT; } - + void executeGcodeLine(const String& gcodeLine){ /* - + Executes a single line of gcode beginning with the character 'G'. If the G code is not included on the front of the line, the code from the previous line will be added. - + */ - + //Handle G-Codes - + int gNumber = extractGcodeValue(gcodeLine,'G', -1); - + if (gNumber == -1){ // If the line does not have a G command gNumber = sys.lastGCommand; // apply the last one } - + switch(gNumber){ case 0: // Rapid positioning case 1: // Linear interpolation @@ -389,18 +389,18 @@ void executeGcodeLine(const String& gcodeLine){ } } - + void executeMcodeLine(const String& gcodeLine){ /* - + Executes a single line of gcode beginning with the character 'M'. - + */ - + //Handle M-Codes - + int mNumber = extractGcodeValue(gcodeLine,'M', -1); - + switch(mNumber){ case 0: // Program Pause / Unconditional Halt / Stop case 1: // Optional Pause / Halt / Sleep @@ -430,14 +430,14 @@ void executeMcodeLine(const String& gcodeLine){ Serial.print(mNumber); Serial.println(F(" unsupported and ignored.")); } - + } void executeOtherCodeLine(const String& gcodeLine){ /* - + Executes a single line of gcode beginning with a character other than 'G', 'B', or 'M'. - + */ if (gcodeLine.length() > 1) { @@ -454,10 +454,10 @@ void executeOtherCodeLine(const String& gcodeLine){ else { Serial.print(F("Command ")); Serial.print(gcodeLine); - Serial.println(F(" too short - ignored.")); + Serial.println(F(" too short - ignored.")); } - -} + +} int findNextGM(const String& readString, const int& startingPoint){ int nextGIndex = readString.indexOf('G', startingPoint); @@ -470,19 +470,19 @@ int findNextGM(const String& readString, const int& startingPoint){ if (nextGIndex == -1) { // if 'G' was not found (and therefore 'M' was not found) nextGIndex = readString.length(); // then use the whole string } - + return nextGIndex; } void sanitizeCommandString(String& cmdString){ /* - Primarily removes comments and some other non supported characters or functions. + Primarily removes comments and some other non supported characters or functions. This is taken heavily from the GRBL project at https://github.com/gnea/grbl */ - + byte line_flags = 0; size_t pos = 0; - + while (cmdString.length() > pos){ if (line_flags) { // Throw away all (except EOL) comment characters and overflow characters. @@ -520,7 +520,7 @@ void sanitizeCommandString(String& cmdString){ } } } - #if defined (verboseDebug) && verboseDebug > 1 + #if defined (verboseDebug) && verboseDebug > 1 // print results Serial.println(F("sCS execution complete")); Serial.println(cmdString); @@ -529,17 +529,17 @@ void sanitizeCommandString(String& cmdString){ byte interpretCommandString(String& cmdString){ /* - + Splits a string into lines of gcode which begin with 'G' or 'M', executing each in order Also executes full lines for 'B' codes, and handles 'T' at beginning of line Assumptions: Leading and trailing white space has already been removed from cmdString cmdString has been converted to upper case - + */ - - size_t firstG; + + size_t firstG; size_t secondG; if (cmdString.length() > 0) { @@ -561,11 +561,11 @@ byte interpretCommandString(String& cmdString){ while(cmdString.length() > 0){ //Extract each line of gcode from the string firstG = findNextGM(cmdString, 0); secondG = findNextGM(cmdString, firstG + 1); - + if(firstG == cmdString.length()){ //If the line contains no G or M letters firstG = 0; //send the whole line } - + if (firstG > 0) { //If there is something before the first 'G' or 'M' gcodeLine = cmdString.substring(0, firstG); #if defined (verboseDebug) && verboseDebug > 0 @@ -574,9 +574,9 @@ byte interpretCommandString(String& cmdString){ Serial.println(gcodeLine); executeOtherCodeLine(gcodeLine); // execute it first } - + gcodeLine = cmdString.substring(firstG, secondG); - + if (gcodeLine.length() > 0){ if (gcodeLine[0] == 'M') { #if defined (verboseDebug) && verboseDebug > 0 @@ -593,9 +593,9 @@ byte interpretCommandString(String& cmdString){ executeGcodeLine(gcodeLine); } } - + cmdString = cmdString.substring(secondG, cmdString.length()); - + } return STATUS_OK; } @@ -618,26 +618,26 @@ void gcodeExecuteLoop(){ } void G1(const String& readString, int G0orG1){ - - /*G1() is the function which is called to process the string if it begins with + + /*G1() is the function which is called to process the string if it begins with 'G01' or 'G00'*/ - + float xgoto; float ygoto; float zgoto; - + float currentXPos = sys.xPosition; float currentYPos = sys.yPosition; - + float currentZPos = zAxis.read(); - + xgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', currentXPos/sys.inchesToMMConversion); ygoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', currentYPos/sys.inchesToMMConversion); zgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', currentZPos/sys.inchesToMMConversion); sys.feedrate = sys.inchesToMMConversion*extractGcodeValue(readString, 'F', sys.feedrate/sys.inchesToMMConversion); - - if (sys.useRelativeUnits){ //if we are using a relative coordinate system - + + if (sys.useRelativeUnits){ //if we are using a relative coordinate system + if(readString.indexOf('X') >= 0){ //if there is an X command xgoto = currentXPos + xgoto; } @@ -648,9 +648,9 @@ void G1(const String& readString, int G0orG1){ zgoto = currentZPos + zgoto; } } - + sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm - + //if the zaxis is attached if(!sysSettings.zAxisAttached){ float threshold = .1; //units of mm @@ -666,16 +666,16 @@ void G1(const String& readString, int G0orG1){ else{ Serial.println(F(" mm")); } - + pause(); //Wait until the z-axis is adjusted - + zAxis.set(zgoto); maslowDelay(1000); } } - - + + if (G0orG1 == 1){ //if this is a regular move coordinatedMove(xgoto, ygoto, zgoto, sys.feedrate); //The XY move is performed @@ -688,27 +688,27 @@ void G1(const String& readString, int G0orG1){ void G2(const String& readString, int G2orG3){ /* - + The G2 function handles the processing of the gcode line for both the command G2 and the command G3 which cut arcs. - + */ - - + + float X1 = sys.xPosition; //does this work if units are inches? (It seems to) float Y1 = sys.yPosition; - + float X2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'X', X1/sys.inchesToMMConversion); float Y2 = sys.inchesToMMConversion*extractGcodeValue(readString, 'Y', Y1/sys.inchesToMMConversion); 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); - + float centerX = X1 + I; float centerY = Y1 + J; - + sys.feedrate = constrain(sys.feedrate, 1, sysSettings.maxFeed); //constrain the maximum feedrate, 35ipm = 900 mmpm - + if (G2orG3 == 2){ arc(X1, Y1, X2, Y2, centerX, centerY, sys.feedrate, CLOCKWISE); } @@ -750,7 +750,7 @@ void G10(const String& readString){ /*The G10() function handles the G10 gcode which re-zeros one or all of the machine's axes.*/ float currentZPos = zAxis.read(); float zgoto = sys.inchesToMMConversion*extractGcodeValue(readString, 'Z', currentZPos/sys.inchesToMMConversion); - + zAxis.set(zgoto); zAxis.endMove(zgoto); zAxis.attach(); @@ -818,7 +818,7 @@ void G38(const String& readString) { long numberOfStepsTaken = 0; float whereAxisShouldBeAtThisStep = startingPos; - + axis->attach(); // zAxis->attach(); diff --git a/cnc_ctrl_v1/GCode.h b/cnc_ctrl_v1/GCode.h index bf8a430e..d2cf12f4 100644 --- a/cnc_ctrl_v1/GCode.h +++ b/cnc_ctrl_v1/GCode.h @@ -44,5 +44,7 @@ void G4(const String&); void G10(const String&); void G38(const String&); void setInchesToMillimetersConversion(float); +extern int SpindlePowerControlPin; +extern int ProbePin; #endif diff --git a/cnc_ctrl_v1/Maslow.h b/cnc_ctrl_v1/Maslow.h index 668cacb7..418b4fec 100644 --- a/cnc_ctrl_v1/Maslow.h +++ b/cnc_ctrl_v1/Maslow.h @@ -9,7 +9,7 @@ GNU General Public License for more details. You should have received a copy of the GNU General Public License along with the Maslow Control Software. If not, see . - + Copyright 2014-2017 Bar Smith*/ // This is the main maslow include file @@ -26,7 +26,7 @@ #include #include -// Define the maslow system include files. This ensures that dependencies are +// Define the maslow system include files. This ensures that dependencies are // loaded in the proper order. Be careful moving these around. #include "Config.h" #include "TimerOne.h" @@ -49,4 +49,4 @@ #include "System.h" #include "SimavrSerial.h" -#endif \ No newline at end of file +#endif diff --git a/cnc_ctrl_v1/Motor.cpp b/cnc_ctrl_v1/Motor.cpp index 9ba89e87..b9cac667 100644 --- a/cnc_ctrl_v1/Motor.cpp +++ b/cnc_ctrl_v1/Motor.cpp @@ -12,7 +12,7 @@ You should have received a copy of the GNU General Public License along with the Maslow Control Software. If not, see . - + Copyright 2014-2017 Bar Smith*/ /* @@ -24,30 +24,39 @@ to be a drop in replacement for a continuous rotation servo. #include "Maslow.h" Motor::Motor(){ - + _attachedState = 0; - - + + } int Motor::setupMotor(const int& pwmPin, const int& pin1, const int& pin2){ - + //store pin numbers as private variables _pwmPin = pwmPin; _pin1 = pin1; _pin2 = pin2; _attachedState = 0; - + + if (TLE5206 == false) { //set pinmodes - pinMode(_pwmPin, OUTPUT); - pinMode(_pin1, OUTPUT); - pinMode(_pin2, OUTPUT); - - //stop the motor - digitalWrite(_pin1, HIGH); - digitalWrite(_pin2, LOW) ; - digitalWrite(_pwmPin, LOW); - + pinMode(_pwmPin, OUTPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, HIGH); + digitalWrite(_pin2, LOW) ; + digitalWrite(_pwmPin, LOW); + } else { + pinMode(_pwmPin, INPUT); + pinMode(_pin1, OUTPUT); + pinMode(_pin2, OUTPUT); + + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } return 1; } @@ -57,11 +66,17 @@ void Motor::attach(){ void Motor::detach(){ _attachedState = 0; - + + if (TLE5206 == false) { //stop the motor digitalWrite(_pin1, HIGH); digitalWrite(_pin2, LOW) ; digitalWrite(_pwmPin, LOW); + } else { + //stop the motor + digitalWrite(_pin1, LOW); + digitalWrite(_pin2, LOW) ; + } } int Motor::lastSpeed(){ @@ -86,45 +101,72 @@ void Motor::write(int speed, bool force){ speed = constrain(speed, -255, 255); _lastSpeed = speed; //saves speed for use in additive write bool forward = (speed > 0); - speed = abs(speed); //remove sign from input because direction is set by control pins on H-bridge - + speed = abs(speed); //remove sign from input because direction is set by control pins on H-bridge + bool usePin1 = ((_pin1 != 4) && (_pin1 != 13) && (_pin1 != 11) && (_pin1 != 12)); // avoid PWM using timer0 or timer1 bool usePin2 = ((_pin2 != 4) && (_pin2 != 13) && (_pin2 != 11) && (_pin2 != 12)); // avoid PWM using timer0 or timer1 - bool usepwmPin = ((_pwmPin != 4) && (_pwmPin != 13) && (_pwmPin != 11) && (_pwmPin != 12)); // avoid PWM using timer0 or timer1 - - - if (forward){ - if (usepwmPin){ - digitalWrite(_pin1 , HIGH ); - digitalWrite(_pin2 , LOW ); - analogWrite(_pwmPin, speed); - } - else if (usePin2) { - digitalWrite(_pin1 , HIGH ); - analogWrite(_pin2 , 255 - speed); // invert drive signals - don't alter speed - digitalWrite(_pwmPin, HIGH); - } - else{ - analogWrite(_pin1 , speed); - digitalWrite(_pin2 , LOW ); - digitalWrite(_pwmPin, HIGH); - } - } - else{ - if (usepwmPin){ - digitalWrite(_pin2 , HIGH); - digitalWrite(_pin1 , LOW ); - analogWrite(_pwmPin, speed); + bool usepwmPin = ((TLE5206 == false) && (_pwmPin != 4) && (_pwmPin != 13) && (_pwmPin != 11) && (_pwmPin != 12)); // avoid PWM using timer0 or timer1 + if (!TLE5206) { + if (forward){ + if (usepwmPin){ + digitalWrite(_pin1 , HIGH ); + digitalWrite(_pin2 , LOW ); + analogWrite(_pwmPin, speed); + } + else if (usePin2) { + digitalWrite(_pin1 , HIGH ); + analogWrite(_pin2 , 255 - speed); // invert drive signals - don't alter speed + digitalWrite(_pwmPin, HIGH); + } + else{ + analogWrite(_pin1 , speed); + digitalWrite(_pin2 , LOW ); + digitalWrite(_pwmPin, HIGH); + } } - else if (usePin1) { - analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed - digitalWrite(_pin2 , HIGH ); - digitalWrite(_pwmPin, HIGH); + else { // reverse or zero speed + if (usepwmPin){ + digitalWrite(_pin2 , HIGH); + digitalWrite(_pin1 , LOW ); + analogWrite(_pwmPin, speed); + } + else if (usePin1) { + analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed + digitalWrite(_pin2 , HIGH ); + digitalWrite(_pwmPin, HIGH); + } + else { + analogWrite(_pin2 , speed); + digitalWrite(_pin1 , LOW ); + digitalWrite(_pwmPin, HIGH); + } } - else { - analogWrite(_pin2 , speed); - digitalWrite(_pin1 , LOW ); - digitalWrite(_pwmPin, HIGH); + } + else { // TLE5206 + if (forward) { + if (speed > 0) { + if (usePin2) { + digitalWrite(_pin1 , HIGH ); + analogWrite(_pin2 , 255 - speed); // invert drive signals - don't alter speed + } + else { + analogWrite(_pin1 , speed); + digitalWrite(_pin2 , LOW ); + } + } + else { // speed = 0 so put on the brakes + digitalWrite(_pin1 , LOW ); + digitalWrite(_pin2 , LOW ); + } + } + else { // reverse + if (usePin1) { + analogWrite(_pin1 , 255 - speed); // invert drive signals - don't alter speed + digitalWrite(_pin2 , HIGH ); + } else { + analogWrite(_pin2 , speed); + digitalWrite(_pin1 , LOW ); + } } } } diff --git a/cnc_ctrl_v1/Motor.h b/cnc_ctrl_v1/Motor.h index b174a08b..8efad4a9 100644 --- a/cnc_ctrl_v1/Motor.h +++ b/cnc_ctrl_v1/Motor.h @@ -49,5 +49,5 @@ int _lastSpeed = 0; }; - + extern bool TLE5206; #endif \ No newline at end of file diff --git a/cnc_ctrl_v1/RingBuffer.cpp b/cnc_ctrl_v1/RingBuffer.cpp index 9ad49aae..c391edc8 100644 --- a/cnc_ctrl_v1/RingBuffer.cpp +++ b/cnc_ctrl_v1/RingBuffer.cpp @@ -12,7 +12,7 @@ You should have received a copy of the GNU General Public License along with the Maslow Control Software. If not, see . - + Copyright 2014-2017 Bar Smith*/ /* @@ -23,15 +23,15 @@ serial data. #include "Maslow.h" RingBuffer::RingBuffer(){ - + } int RingBuffer::write(char letter){ /* - + Write one character into the ring buffer. Return 0 on success Return 1 on buffer overflow - + */ if (letter != '?'){ //ignore question marks because grbl sends them all the time _buffer[_endOfString] = letter; @@ -43,11 +43,11 @@ int RingBuffer::write(char letter){ char RingBuffer::read(){ /* - + Read one character from the ring buffer. - + */ - + char letter; if (_beginningOfString == _endOfString){ letter = '\0'; //if the buffer is empty return null @@ -57,15 +57,15 @@ char RingBuffer::read(){ _buffer[_beginningOfString] = '\0'; //set the read character to null so it cannot be read again _incrementBeginning(); //and increment the pointer } - + return letter; } int RingBuffer::numberOfLines() { /* - + Return the number of full lines (as determined by \n terminations) in the buffer - + */ int lineCount = 0; @@ -77,19 +77,19 @@ int RingBuffer::numberOfLines() { } _incrementVariable(&i); // go to the next character in the buffer } - + return lineCount; } void RingBuffer::readLine(String &lineToReturn){ /* - + Return one line (terminated with \n) from the buffer if there are no full lines in the buffer, passed string will be empty - + */ lineToReturn = ""; // begin with an empty string - + if (numberOfLines() > 0) { // there is at least one full line in the buffer char lastReadValue = '\0'; while(lastReadValue != '\n'){ //read until the end of the line is found, building the string @@ -101,10 +101,10 @@ void RingBuffer::readLine(String &lineToReturn){ void RingBuffer::prettyReadLine(String &lineToReturn){ /* - + Return one line (terminated with \n) from the buffer, but in all uppercase with no leading or trailing whitespaces - + */ readLine(lineToReturn); lineToReturn.trim(); // remove leading and trailing white space @@ -120,7 +120,7 @@ void RingBuffer::print(){ Serial.println(_beginningOfString); Serial.print(F("Buffer End: ")); Serial.println(_endOfString); - + Serial.print(F("Buffer Contents: ")); int i = _beginningOfString; while(i != _endOfString){ @@ -128,39 +128,39 @@ void RingBuffer::print(){ Serial.print(F("\\n")); } else if (_buffer[i] == '\r') { - Serial.print(F("\\r")); + Serial.print(F("\\r")); } else if (_buffer[i] == '\t') { - Serial.print(F("\\t")); + Serial.print(F("\\t")); } else { - Serial.print(_buffer[i]); + Serial.print(_buffer[i]); } _incrementVariable(&i); } - + Serial.println(F("(End of Buffer)")); - + } void RingBuffer::_incrementBeginning(){ /* - + Increment the pointer to the beginning of the ring buffer by one. - + */ - - if (_beginningOfString == _endOfString) + + if (_beginningOfString == _endOfString) return; //don't allow the beginning to pass the end - else + else _beginningOfString = (_beginningOfString + 1) % INCBUFFERLENGTH; //move the beginning up one and wrap to zero based upon INCBUFFERLENGTH } int RingBuffer::_incrementEnd(){ /* - + Increment the pointer to the end of the ring buffer by one. - + */ if ( spaceAvailable() == 0 ) { Serial.println(F("Buffer overflow!")); @@ -174,7 +174,7 @@ int RingBuffer::_incrementEnd(){ void RingBuffer::_incrementVariable(int* variable){ /* - Increment the target variable. + Increment the target variable. */ *variable = (*variable + 1 ) % INCBUFFERLENGTH; } @@ -194,7 +194,7 @@ int RingBuffer::length(void) if ( _endOfString >= _beginningOfString ) // Linear return _endOfString - _beginningOfString ; else // must have rolled - return ( INCBUFFERLENGTH - _beginningOfString + _endOfString); + return ( INCBUFFERLENGTH - _beginningOfString + _endOfString); } @@ -202,7 +202,7 @@ void RingBuffer::empty(){ /* Empty the contents of the ring buffer */ - + _beginningOfString = 0; _endOfString = 0; } diff --git a/cnc_ctrl_v1/Settings.cpp b/cnc_ctrl_v1/Settings.cpp index 23e17d40..04770678 100644 --- a/cnc_ctrl_v1/Settings.cpp +++ b/cnc_ctrl_v1/Settings.cpp @@ -24,14 +24,14 @@ Copyright 2014-2017 Bar Smith*/ #include void settingsLoadFromEEprom(){ - /* + /* Loads data from EEPROM if EEPROM data is valid, only called on startup - + Settings are stored starting at address 340 all the way up. */ settingsVersion_t settingsVersionStruct; settings_t tempSettings; - + settingsReset(); // Load default values first EEPROM.get(300, settingsVersionStruct); EEPROM.get(340, tempSettings); @@ -43,7 +43,7 @@ void settingsLoadFromEEprom(){ else { reportStatusMessage(STATUS_SETTING_READ_FAIL); } - + // Apply settings setPWMPrescalers(int(sysSettings.fPWM)); kinematics.recomputeGeometry(); @@ -56,11 +56,11 @@ void settingsLoadFromEEprom(){ } void settingsReset() { - /* + /* Loads default data into settings, many of these values are approximations from the an ideal stock frame. Other values are just the recommended value. Ideally we want these defaults to match the defaults in GroundControl - so that if a value is not changed by a user or is not used, it doesn't + so that if a value is not changed by a user or is not used, it doesn't need to be updated here. */ sysSettings.machineWidth = 2438.4; // float machineWidth; @@ -130,9 +130,9 @@ void settingsWipe(byte resetType){ } void settingsSaveToEEprom(){ - /* + /* Saves settings to EEPROM, only called when settings change - + Settings are stored starting at address 340 all the way up. */ settingsVersion_t settingsVersionStruct = {SETTINGSVERSION, EEPROMVALIDDATA}; @@ -141,9 +141,9 @@ void settingsSaveToEEprom(){ } void settingsSaveStepstoEEprom(){ - /* + /* Saves position to EEPROM, is called frequently by execSystemRealtime - + Steps are saved in address 310 -> 339. Room for expansion for additional axes in the future. */ @@ -160,7 +160,7 @@ void settingsSaveStepstoEEprom(){ } void settingsLoadStepsFromEEprom(){ - /* + /* Loads position to EEPROM, is called on startup. Steps are saved in address 310 -> 339. Room for expansion for additional @@ -194,8 +194,8 @@ void settingsLoadStepsFromEEprom(){ void settingsLoadOldSteps(){ /* - Loads the old version of step settings, only called once encoder steps - and distance per rotation have been loaded. Wipes the old data once + Loads the old version of step settings, only called once encoder steps + and distance per rotation have been loaded. Wipes the old data once incorporated to prevent oddities in the future */ if (sys.state == STATE_OLD_SETTINGS){ @@ -217,10 +217,10 @@ void settingsLoadOldSteps(){ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ /* - Alters individual settings which are then stored to EEPROM. Returns a - status message byte value + Alters individual settings which are then stored to EEPROM. Returns a + status message byte value */ - + // We can add whatever sanity checks we want here and error out if we like switch(parameter) { case 0: case 1: case 2: case 3: case 4: case 5: case 6: case 7: case 8: @@ -228,43 +228,43 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ case 0: sysSettings.machineWidth = value; break; - case 1: + case 1: sysSettings.machineHeight = value; break; - case 2: + case 2: sysSettings.distBetweenMotors = value; break; - case 3: + case 3: sysSettings.motorOffsetY = value; break; - case 4: + case 4: sysSettings.sledWidth = value; break; - case 5: + case 5: sysSettings.sledHeight = value; break; - case 6: + case 6: sysSettings.sledCG = value; break; - case 7: + case 7: sysSettings.kinematicsType = value; break; - case 8: + case 8: sysSettings.rotationDiskRadius = value; break; } kinematics.init(); break; - case 9: + case 9: sysSettings.axisDetachTime = value; break; - case 10: + case 10: sysSettings.chainLength = value; break; - case 11: + case 11: sysSettings.originalChainLength = value; break; - case 12: + case 12: sysSettings.encoderSteps = value; leftAxis.changeEncoderResolution(&sysSettings.encoderSteps); rightAxis.changeEncoderResolution(&sysSettings.encoderSteps); @@ -276,7 +276,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ } kinematics.init(); break; - case 13: + case 13: sysSettings.distPerRot = value; kinematics.R = (sysSettings.distPerRot)/(2.0 * 3.14159); if (sys.oldSettingsFlag){ @@ -287,7 +287,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ } kinematics.init(); break; - case 15: + case 15: sysSettings.maxFeed = value; break; case 16: @@ -296,10 +296,10 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ case 17: sysSettings.spindleAutomateType = static_cast(value); break; - case 18: + case 18: sysSettings.maxZRPM = value; break; - case 19: + case 19: sysSettings.zDistPerRot = value; zAxis.changePitch(&sysSettings.zDistPerRot); if (sys.oldSettingsFlag){ @@ -309,7 +309,7 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ } } break; - case 20: + case 20: sysSettings.zEncoderSteps = value; zAxis.changeEncoderResolution(&sysSettings.zEncoderSteps); if (sys.oldSettingsFlag){ @@ -324,25 +324,25 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ case 21: sysSettings.KpPos = value; break; - case 22: + case 22: sysSettings.KiPos = value; break; - case 23: + case 23: sysSettings.KdPos = value; break; - case 24: + case 24: sysSettings.propWeightPos = value; break; - case 25: + case 25: sysSettings.KpV = value; break; - case 26: + case 26: sysSettings.KiV = value; break; - case 27: + case 27: sysSettings.KdV = value; break; - case 28: + case 28: sysSettings.propWeightV = value; break; } @@ -351,28 +351,28 @@ byte settingsStoreGlobalSetting(const byte& parameter,const float& value){ break; case 29: case 30: case 31: case 32: case 33: case 34: case 35: case 36: switch(parameter) { - case 29: + case 29: sysSettings.zKpPos = value; break; - case 30: + case 30: sysSettings.zKiPos = value; break; - case 31: + case 31: sysSettings.zKdPos = value; break; - case 32: + case 32: sysSettings.zPropWeightPos = value; break; - case 33: + case 33: sysSettings.zKpV = value; break; - case 34: + case 34: sysSettings.zKiV = value; break; - case 35: + case 35: sysSettings.zKdV = value; break; - case 36: + case 36: sysSettings.zPropWeightV = value; break; } diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 5e913521..62957ef4 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -19,10 +19,13 @@ Copyright 2014-2017 Bar Smith*/ #include "Maslow.h" +bool TLE5206; + // extern values using AUX pins defined in configAuxLow() and configAuxHigh() int SpindlePowerControlPin; // output for controlling spindle power int ProbePin; // use this input for zeroing zAxis with G38.2 gcode + void calibrateChainLengths(String gcodeLine){ /* The calibrateChainLengths function lets the machine know that the chains are set to a given length where each chain is ORIGINCHAINLEN @@ -86,6 +89,9 @@ void setupAxes(){ int aux4; int aux5; int aux6; + int aux7; + int aux8; + int aux9; //read the pins which indicate the PCB version int pcbVersion = getPCBVersion(); @@ -184,6 +190,40 @@ void setupAxes(){ aux5 = A7; aux6 = A6; } + else if(pcbVersion == 3){ // TLE5206 + //TLE5206 PCB v1.3 Detected + //MP1 - Right Motor + encoder1A = 20; // INPUT + encoder1B = 21; // INPUT + in1 = 6; // OUTPUT + in2 = 4; // OUTPUT + enA = 5; // errorFlag + + //MP2 - Z-axis + encoder2A = 19; // INPUT + encoder2B = 18; // INPUT + in3 = 7; // OUTPUT + in4 = 9; // OUTPUT + enB = 8; // errorFlag + + //MP3 - Left Motor + encoder3A = 2; // INPUT + encoder3B = 3; // INPUT + in5 = 10; // OUTPUT + in6 = 11; // OUTPUT + enC = 12; // errorFlag + + //AUX pins + aux1 = 40; + aux2 = 41; + aux3 = 42; + aux4 = 43; + aux5 = 68; + aux6 = 69; + aux7 = 45; + aux8 = 46; + aux9 = 47; + } if(sysSettings.chainOverSprocket == 1){ leftAxis.setup (enC, in6, in5, encoder3B, encoder3A, 'L', LOOPINTERVAL); @@ -204,6 +244,9 @@ void setupAxes(){ // "warning: variable ‘xxxxx’ set but not used [-Wunused-but-set-variable]" // for AUX pins defined but not connected configAuxLow(aux1, aux2, aux3, aux4, aux5, aux6); + if(pcbVersion == 3){ // TLE5206 + configAuxHigh(aux7, aux8, aux9); + } } // Assign AUX pins to extern variables used by functions like Spindle and Probe @@ -212,6 +255,8 @@ void configAuxLow(int aux1, int aux2, int aux3, int aux4, int aux5, int aux6) { ProbePin = aux4; // use this input for zeroing zAxis with G38.2 gcode } +void configAuxHigh(int aux7, int aux8, int aux9) { +} int getPCBVersion(){ pinMode(VERS1,INPUT_PULLUP); @@ -224,17 +269,18 @@ int getPCBVersion(){ switch (pinCheck) { // boards v1.1, v1.2, v1.3 don't strap VERS3-6 low case B111101: case B111110: case B111111: // v1.1, v1.2, v1.3 - pinCheck -= B111100; // strip off the unstrapped bits - // TLE5206 = false; + pinCheck &= B000011; // strip off the unstrapped bits + TLE5206 = false; break; - case B110100: // board v1.4 doesn't strap VERS5-6 low - pinCheck -= B110000; // strip off the unstrapped bits - // TLE5206 = true; + case B110100: case B000100: // some versions of board v1.4 don't strap VERS5-6 low + pinCheck &= B000111; // strip off the unstrapped bits + TLE5206 = true; break; } return pinCheck - 1; } + // // PWM frequency change // presently just sets the default value @@ -292,6 +338,7 @@ void setPWMPrescalers(int prescalerChoice) { TCCR4B |= prescalerChoice; // pins 6, 7, 8 } + // This should likely go away and be handled by setting the pause flag and then // pausing in the execSystemRealtime function // Need to check if all returns from this subsequently look to sys.stop diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index 5fdf55c1..4763022e 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -89,6 +89,5 @@ void systemReset(); byte systemExecuteCmdstring(String&); void setPWMPrescalers(int prescalerChoice); void configAuxLow(int A1, int A2, int A3, int A4, int A5, int A6); - - +void configAuxHigh(int A7, int A8, int A9); #endif diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index 03804b93..3880cfd6 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -30,6 +30,9 @@ * and restart the IDE. */ + +// TLE5206 version + #include "Maslow.h" // Define system global state structure @@ -54,7 +57,9 @@ void setup(){ Serial.begin(57600); Serial.print(F("PCB v1.")); Serial.print(getPCBVersion()); + if (TLE5206 == true) { Serial.print(F(" TLE5206 ")); } Serial.println(F(" Detected")); + Serial.println(F("TLE5206-release firmware")); sys.inchesToMMConversion = 1; settingsLoadFromEEprom(); setupAxes();