diff --git a/cnc_ctrl_v1/Config.h b/cnc_ctrl_v1/Config.h index 4dd06b37..501139d2 100644 --- a/cnc_ctrl_v1/Config.h +++ b/cnc_ctrl_v1/Config.h @@ -9,10 +9,10 @@ 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 file contains precompile configuration settings that apply to the +// This file contains precompile configuration settings that apply to the // whole system #ifndef config_h @@ -20,7 +20,7 @@ // 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 +#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 @@ -35,30 +35,22 @@ #define LOOPINTERVAL 10000 // What is the frequency of the PID loop in microseconds -// Define extra pins -#define AUX1 17 -#define AUX2 16 -#define AUX3 15 -#define AUX4 14 -#define SpindlePowerControlPin AUX1 // output for controlling spindle power -#define ProbePin AUX4 // use this input for zeroing zAxis with G38.2 gcode - // 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 +#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 +#define POSITIONTIMEOUT 200 // The minimum number of milliseconds between + // position reports sent to Ground Control. This + // cannot be larger than the connection timout in // Ground Control which is 2000, a smaller number // takes more processing time for sending data // a larger number make position updates in GC less // smooth. This is only a minimum, and the actual - // timeout could be significantly larger. + // timeout could be significantly larger. #endif diff --git a/cnc_ctrl_v1/Probe.cpp b/cnc_ctrl_v1/Probe.cpp index f9340dc3..619fc09a 100644 --- a/cnc_ctrl_v1/Probe.cpp +++ b/cnc_ctrl_v1/Probe.cpp @@ -19,6 +19,8 @@ Copyright 2014-2017 Bar Smith*/ #include "Maslow.h" +// the variable probePin is assigned in configAuxLow() in System.cpp + bool checkForProbeTouch(const int& probePin) { /* Check to see if ProbePin has gone LOW @@ -28,4 +30,4 @@ bool checkForProbeTouch(const int& probePin) { return 1; } return 0; -} \ No newline at end of file +} diff --git a/cnc_ctrl_v1/Spindle.cpp b/cnc_ctrl_v1/Spindle.cpp index 9dec8125..3384d848 100644 --- a/cnc_ctrl_v1/Spindle.cpp +++ b/cnc_ctrl_v1/Spindle.cpp @@ -9,20 +9,22 @@ 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 contains all of the Spindle commands #include "Maslow.h" +// the variable SpindlePowerControlPin is assigned in configAuxLow() in System.cpp + // Globals for Spindle control, both poorly named -Servo myservo; // create servo object to control a servo +Servo myservo; // create servo object to control a servo void setSpindlePower(bool powerState) { /* * Turn spindle on or off depending on powerState - */ + */ boolean useServo = !sysSettings.spindleAutomate; boolean activeHigh = true; int delayAfterChange = 1000; // milliseconds @@ -30,14 +32,14 @@ void setSpindlePower(bool powerState) { int servoOn = 180; // degrees int servoOff = 0; // degrees int servoDelay = 2000; // milliseconds - + // Now for the main code - #if defined (verboseDebug) && verboseDebug > 1 + #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F("Spindle control uses pin ")); Serial.print(SpindlePowerControlPin); #endif if (useServo) { // use a servo to control a standard wall switch - #if defined (verboseDebug) && verboseDebug > 1 + #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F(" with servo (idle=")); Serial.print(servoIdle); Serial.print(F(", on=")); @@ -66,7 +68,7 @@ void setSpindlePower(bool powerState) { myservo.detach(); // stop servo control } else { // use a digital I/O pin to control a relay - #if defined (verboseDebug) && verboseDebug > 1 + #if defined (verboseDebug) && verboseDebug > 1 Serial.print(F(" as digital output, active ")); if (activeHigh) Serial.println(F("high")); else Serial.println(F("low")); @@ -84,4 +86,4 @@ void setSpindlePower(bool powerState) { } } maslowDelay(delayAfterChange); -} \ No newline at end of file +} diff --git a/cnc_ctrl_v1/System.cpp b/cnc_ctrl_v1/System.cpp index 5f16cf90..134e0d59 100644 --- a/cnc_ctrl_v1/System.cpp +++ b/cnc_ctrl_v1/System.cpp @@ -19,44 +19,48 @@ Copyright 2014-2017 Bar Smith*/ #include "Maslow.h" +// 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 in length */ - + if (extractGcodeValue(gcodeLine, 'L', 0)){ //measure out the left chain Serial.println(F("Measuring out left chain")); singleAxisMove(&leftAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); - + Serial.print(leftAxis.read()); Serial.println(F("mm")); - + leftAxis.detach(); } else if(extractGcodeValue(gcodeLine, 'R', 0)){ //measure out the right chain Serial.println(F("Measuring out right chain")); singleAxisMove(&rightAxis, sysSettings.originalChainLength, (sysSettings.maxFeed * .9)); - + Serial.print(rightAxis.read()); Serial.println(F("mm")); - + rightAxis.detach(); } - + } void setupAxes(){ /* - + Detect the version of the Arduino shield connected, and use the appropriate pins - + This function runs before the serial port is open so the version is not printed here - + */ - + // These shouldn't be CAPS, they are not precompile defines int ENCODER1A; int ENCODER1B; @@ -64,21 +68,28 @@ void setupAxes(){ int ENCODER2B; int ENCODER3A; int ENCODER3B; - + int IN1; int IN2; int IN3; int IN4; int IN5; int IN6; - + int ENA; int ENB; int ENC; - + + int AUX1; + int AUX2; + int AUX3; + int AUX4; + int AUX5; + int AUX6; + //read the pins which indicate the PCB version int pcbVersion = getPCBVersion(); - + if(pcbVersion == 0){ //Beta PCB v1.0 Detected //MP1 - Right Motor @@ -87,20 +98,28 @@ void setupAxes(){ IN1 = 9; // OUTPUT IN2 = 8; // OUTPUT ENA = 6; // PWM - + //MP2 - Z-axis ENCODER2A = 2; // INPUT ENCODER2B = 3; // INPUT IN3 = 11; // OUTPUT IN4 = 10; // OUTPUT ENB = 7; // PWM - + //MP3 - Left Motor ENCODER3A = 21; // INPUT ENCODER3B = 20; // INPUT IN5 = 12; // OUTPUT IN6 = 13; // OUTPUT ENC = 5; // PWM + + //AUX pins + AUX1 = 17; + AUX2 = 16; + AUX3 = 15; + AUX4 = 14; + AUX5 = 0; // warning! this is the serial TX line on the Mega2560 + AUX6 = 1; // warning! this is the serial RX line on the Mega2560 } else if(pcbVersion == 1){ //PCB v1.1 Detected @@ -110,38 +129,46 @@ void setupAxes(){ IN1 = 6; // OUTPUT IN2 = 4; // OUTPUT ENA = 5; // PWM - + //MP2 - Z-axis ENCODER2A = 19; // INPUT ENCODER2B = 18; // INPUT IN3 = 9; // OUTPUT IN4 = 7; // OUTPUT ENB = 8; // PWM - + //MP3 - Left Motor ENCODER3A = 2; // INPUT ENCODER3B = 3; // INPUT IN5 = 10; // OUTPUT IN6 = 11; // OUTPUT ENC = 12; // PWM + + //AUX pins + AUX1 = 17; + AUX2 = 16; + AUX3 = 15; + AUX4 = 14; + AUX5 = A7; + AUX6 = A6; } else if(pcbVersion == 2){ //PCB v1.2 Detected - + //MP1 - Right Motor ENCODER1A = 20; // INPUT ENCODER1B = 21; // INPUT IN1 = 4; // OUTPUT IN2 = 6; // OUTPUT ENA = 5; // PWM - + //MP2 - Z-axis ENCODER2A = 19; // INPUT ENCODER2B = 18; // INPUT IN3 = 7; // OUTPUT IN4 = 9; // OUTPUT ENB = 8; // PWM - + //MP3 - Left Motor ENCODER3A = 2; // INPUT ENCODER3B = 3; // INPUT @@ -149,7 +176,13 @@ void setupAxes(){ IN6 = 12; // OUTPUT ENC = 10; // PWM - + //AUX pins + AUX1 = 17; + AUX2 = 16; + AUX3 = 15; + AUX4 = 14; + AUX5 = A7; + AUX6 = A6; } if(sysSettings.chainOverSprocket == 1){ @@ -160,13 +193,26 @@ void setupAxes(){ leftAxis.setup (ENC, IN5, IN6, ENCODER3A, ENCODER3B, 'L', LOOPINTERVAL); rightAxis.setup(ENA, IN2, IN1, ENCODER1B, ENCODER1A, 'R', LOOPINTERVAL); } - + zAxis.setup (ENB, IN3, IN4, ENCODER2B, ENCODER2A, 'Z', LOOPINTERVAL); leftAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); rightAxis.setPIDValues(&sysSettings.KpPos, &sysSettings.KiPos, &sysSettings.KdPos, &sysSettings.propWeightPos, &sysSettings.KpV, &sysSettings.KiV, &sysSettings.KdV, &sysSettings.propWeightV); zAxis.setPIDValues(&sysSettings.zKpPos, &sysSettings.zKiPos, &sysSettings.zKdPos, &sysSettings.zPropWeightPos, &sysSettings.zKpV, &sysSettings.zKiV, &sysSettings.zKdV, &sysSettings.zPropWeightV); + + // implement the AUXx values that are 'used'. This accomplishes setting their values at runtime. + // Using a separate function is a compiler work-around to avoid + // "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); } +// Assign AUX pins to extern variables used by functions like Spindle and Probe +void configAuxLow(int AUX1, int AUX2, int AUX3, int AUX4, int AUX5, int AUX6) { + SpindlePowerControlPin = AUX1; // output for controlling spindle power + ProbePin = AUX4; // use this input for zeroing zAxis with G38.2 gcode +} + + int getPCBVersion(){ return (8*digitalRead(53) + 4*digitalRead(52) + 2*digitalRead(23) + 1*digitalRead(22)) - 1; } @@ -209,7 +255,7 @@ void setPWMPrescalers(int prescalerChoice) { // Code: TCCR2B = (TCCR2B & 0xF8) | value ; // —————————————————————————————- // Timers 3, 4 ( Pin 2, 3, 5), (Pin 6, 7, 8) -// +// // Value Divisor Frequency // 0x01 1 31.374 KHz // 0x02 8 3.921 Khz @@ -259,24 +305,24 @@ void setPWMPrescalers() { // Need to check if all returns from this subsequently look to sys.stop void pause(){ /* - + The pause command pauses the machine in place without flushing the lines stored in the machine's buffer. - - When paused the machine enters a while() loop and doesn't exit until the '~' cycle resume command + + When paused the machine enters a while() loop and doesn't exit until the '~' cycle resume command is issued from Ground Control. - + */ - + bit_true(sys.pause, PAUSE_FLAG_USER_PAUSE); Serial.println(F("Maslow Paused")); - + while(bit_istrue(sys.pause, PAUSE_FLAG_USER_PAUSE)) { - + // Run realtime commands execSystemRealtime(); if (sys.stop){return;} - } + } } @@ -291,13 +337,13 @@ void maslowDelay(unsigned long waitTimeMs) { * Provides a time delay while holding the machine position, reading serial commands, * and periodically sending the machine position to Ground Control. This prevents * Ground Control from thinking that the connection is lost. - * + * * This is similar to the pause() command above, but provides a time delay rather than * waiting for the user (through Ground Control) to tell the machine to continue. */ - + unsigned long startTime = millis(); - + while ((millis() - startTime) < waitTimeMs){ execSystemRealtime(); if (sys.stop){return;} @@ -326,29 +372,29 @@ void systemSaveAxesPosition(){ } } -// This should be the ultimate fallback, it would be best if we didn't even need +// This should be the ultimate fallback, it would be best if we didn't even need // something like this at all // TODO delete this function, we are not even using it anymore void _watchDog(){ /* If: - No incoming serial in 5 seconds + No incoming serial in 5 seconds Motors are detached Nothing in Serial buffer Watchdog has not run in 5 seconds Then: Send an ok message - + This fixes the issue where the machine is ready, but Ground Control doesn't know the machine is ready and the system locks up. */ static unsigned long lastRan = millis(); - + if ( millis() - sys.lastSerialRcvd > 5000 && - (millis() - lastRan) > 5000 && + (millis() - lastRan) > 5000 && !leftAxis.attached() and !rightAxis.attached() and !zAxis.attached() && incSerialBuffer.length() == 0 ){ - #if defined (verboseDebug) && verboseDebug > 0 + #if defined (verboseDebug) && verboseDebug > 0 Serial.println(F("_watchDog requesting new code")); #endif reportStatusMessage(STATUS_OK); @@ -357,7 +403,7 @@ void _watchDog(){ } void systemReset(){ - /* + /* Stops everything and resets the arduino */ leftAxis.detach(); @@ -448,14 +494,14 @@ byte systemExecuteCmdstring(String& cmdString){ // if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { // sys.state = STATE_HOMING; // Set system state variable // // Only perform homing if Grbl is idle or lost. - // + // // // TODO: Likely not required. // if (system_check_safety_door_ajar()) { // Check safety door switch before homing. // bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR); // protocol_execute_realtime(); // Enter safety door mode. // } - // - // + // + // // mc_homing_cycle(); // if (!sys.abort) { // Execute startup scripts after successful homing. // sys.state = STATE_IDLE; // Set to IDLE when complete. diff --git a/cnc_ctrl_v1/System.h b/cnc_ctrl_v1/System.h index 670db5c5..3c7f2967 100644 --- a/cnc_ctrl_v1/System.h +++ b/cnc_ctrl_v1/System.h @@ -39,7 +39,7 @@ Copyright 2014-2017 Bar Smith*/ #define STATE_CYCLE bit(3) // Cycle is running or motions are being executed. #define STATE_HOLD bit(4) // Active feed hold #define STATE_SAFETY_DOOR bit(5) // Safety door is ajar. Feed holds and de-energizes system. -#define STATE_MOTION_CANCEL bit(6) // Motion cancel by feed hold and return to idle. +#define STATE_MOTION_CANCEL bit(6) // Motion cancel by feed hold and return to idle. // Define old settings flag details #define NEED_ENCODER_STEPS bit(0) @@ -56,7 +56,7 @@ typedef struct { float xPosition; // Cartessian position of XY axes float yPosition; // Cached because calculating position is intensive float steps[3]; // Encoder position of axes - bool useRelativeUnits; // + 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 lastTool; //Stores the value of the last tool number eg: T4 -> 4 @@ -74,6 +74,8 @@ extern Axis zAxis; extern RingBuffer incSerialBuffer; extern Kinematics kinematics; extern byte systemRtExecAlarm; +extern int SpindlePowerControlPin; +extern int ProbePin; void calibrateChainLengths(String); void setupAxes(); @@ -86,6 +88,7 @@ void systemSaveAxesPosition(); void systemReset(); byte systemExecuteCmdstring(String&); void setPWMPrescalers(int prescalerChoice); +void configAuxLow(int A1, int A2, int A3, int A4, int A5, int A6); #endif diff --git a/cnc_ctrl_v1/cnc_ctrl_v1.ino b/cnc_ctrl_v1/cnc_ctrl_v1.ino index cf5d85e0..03804b93 100644 --- a/cnc_ctrl_v1/cnc_ctrl_v1.ino +++ b/cnc_ctrl_v1/cnc_ctrl_v1.ino @@ -14,8 +14,8 @@ /* To the projects contributers: - * - * it is highly recommended to activate warning output of the arduino gcc compiler. + * + * it is highly recommended to activate warning output of the arduino gcc compiler. * Compiler warnings are a great help to keep the codebase clean and can give clues * to potentally wrong code. Also, if a codebase produces too many warnings it gets * more likely that possibly important warnings could be overlooked. @@ -75,6 +75,7 @@ void setup(){ Serial.println(F("Grbl v1.00")); // Why GRBL? Apparently because some programs are silly and look for this as an initialization command Serial.println(F("ready")); reportStatusMessage(STATUS_OK); + } void runsOnATimer(){