Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
31 commits
Select commit Hold shift + click to select a range
8c9b2fe
Add Missing Kinematics.Init()
madgrizzle Aug 20, 2019
7748db8
add B99 command to control FAKE_SERVO mode
blurfl Aug 22, 2019
22aad90
Merge pull request #529 from madgrizzle/patch-8
MaslowCommunityGardenRobot Aug 22, 2019
ad381bc
Merge pull request #530 from blurfl/B99-FAKE_SERVO-control
MaslowCommunityGardenRobot Aug 24, 2019
5d351a3
tighten up FAKE_SERVO access
blurfl Aug 30, 2019
768524c
Merge pull request #532 from blurfl/tighten-up-FAKE_SERVO-access-control
MaslowCommunityGardenRobot Sep 1, 2019
dc6c23f
remove characters within a comment
blurfl Oct 6, 2019
400db40
Merge pull request #534 from blurfl/fix-comment-handling
MaslowCommunityGardenRobot Oct 8, 2019
2ed6fff
gb0101010101-g2-arc-z-optional: Do not perform Z axis movement on G2 …
Feb 25, 2020
604f365
Merge pull request #540 from gb0101010101/gb0101010101-g2-arc-z-optional
BarbourSmith Mar 4, 2020
12af38c
Add support for G2 & G3 commands that use radius R instead of I & J.
May 15, 2020
408b4d9
Z Axis limits
ariasr May 18, 2020
71d5cc9
Changes requested
ariasr May 19, 2020
8095dec
Merge pull request #543 from ariasr/master
MaslowCommunityGardenRobot May 20, 2020
91eefe0
Revert pull pull request template to original version
BarbourSmith May 20, 2020
25aaf81
Merge pull request #544 from gb0101010101/gb0101010101-g2-g3-support-…
MaslowCommunityGardenRobot May 21, 2020
a2f3b40
Merge pull request #545 from MaslowCNC/Revert-pull-request-template
MaslowCommunityGardenRobot May 22, 2020
35cce7d
Spindle pwm pin 45 added
Orob-Maslow Sep 9, 2020
b9c98bb
Merge remote-tracking branch 'upstream/master' into HoleySpindlePwm
Orob-Maslow Sep 10, 2020
1811d70
Update Settings.cpp
Orob-Maslow Sep 13, 2020
aae7240
Chain length error fix
Orob-Maslow Sep 13, 2020
c073f52
Update System.cpp
Orob-Maslow Sep 13, 2020
e80f1f7
Merge branch 'HoleySpindlePwm'
Orob-Maslow Sep 13, 2020
d408d13
Update cnc_ctrl_v1.ino
Orob-Maslow Sep 15, 2020
d6eb50c
Spindle pwm pin only works when m3/m4 spindle is ON
Orob-Maslow Sep 16, 2020
10b1fa1
51.29 added v1.5 shield
Orob-Maslow Nov 24, 2020
8ee4f92
Update System.cpp
Orob-Maslow Nov 25, 2020
2883762
Update System.cpp
Orob-Maslow Nov 25, 2020
ddb1c6c
Update System.cpp
Orob-Maslow Nov 25, 2020
0b0b358
updated board detection check
Orob-Maslow Nov 25, 2020
733a45a
purge diff files from repo
Orob-Maslow Nov 25, 2020
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
67 changes: 58 additions & 9 deletions cnc_ctrl_v1/Axis.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,26 @@ void Axis::initializePID(const unsigned long& loopInterval){
}

void Axis::write(const float& targetPosition){
_timeLastMoved = millis();
_pidSetpoint = targetPosition/ *_mmPerRotation;
return;

_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;
}
}

// update target position
_pidSetpoint = targetPosition/ *_mmPerRotation;
return;
}

float Axis::read(){
Expand All @@ -61,11 +78,26 @@ 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);

motorGearboxEncoder.encoder.write((newAxisPosition * *_encoderSteps)/ *_mmPerRotation);
}

long Axis::steps(){
Expand All @@ -85,6 +117,7 @@ void Axis::setSteps(const long& steps){

void Axis::computePID(){


if (FAKE_SERVO_STATE == FAKE_SERVO_PERMITTED) {
if (motorGearboxEncoder.motor.attached()){
// Adds up to 10% error just to simulate servo noise
Expand Down Expand Up @@ -224,12 +257,28 @@ void Axis::detachIfIdle(){
}

void Axis::endMove(const float& finalTarget){

_timeLastMoved = millis();

// Check that the Z axis position is within limits specified 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;

_pidSetpoint = finalTarget/ *_mmPerRotation;

}


void Axis::stop(){
/*

Expand Down
9 changes: 9 additions & 0 deletions cnc_ctrl_v1/Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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',
Expand Down Expand Up @@ -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
Expand All @@ -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
129 changes: 127 additions & 2 deletions cnc_ctrl_v1/GCode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ Copyright 2014-2017 Bar Smith*/

#include "Maslow.h"
#include <EEPROM.h>
#include "math.h"

maslowRingBuffer incSerialBuffer;
String readyCommandString = ""; //KRK why is this a global?
Expand Down Expand Up @@ -371,11 +372,75 @@ byte executeBcodeLine(const String& gcodeLine){

// Use 'B99 ON' to set FAKE_SERVO mode on,
// 'B99' with no parameter, or any parameter other than 'ON'
if(gcodeLine.substring(0, 3) == "B17"){
//The B17 sets the current Z position as Upper Limit for zAxis

if(!isnan(zAxis.read())){

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;

} 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(!isnan(zAxis.read())){
settingsStoreGlobalSetting(byte(44), zAxis.read());

Serial.print(F("Lower limit set to: "));
Serial.println(isnan(sysSettings.zAxisLowerLimit) ? F(" "): String(sysSettings.zAxisLowerLimit / sys.inchesToMMConversion));

return STATUS_OK;

} else {

Serial.println(F("Error setting limit"));

return STATUS_GCODE_INVALID_TARGET;

}
}
if(gcodeLine.substring(0, 3) == "B19"){
//The B19 clears limits for zAxis

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;
}

// 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 ]
// The status of FAKE_SERVO mode is stored in EEPROM[ 4095 ]
// 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.
Expand All @@ -398,7 +463,21 @@ 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 (sys.SpindlePower){
if (setSpindleSpeed(sNumber)){
sys.SpindleSpeed = sNumber;
}
}else{
Serial.println("spindle speed not set when spindle is off");
}
}
void executeGcodeLine(const String& gcodeLine){
/*

Expand Down Expand Up @@ -566,6 +645,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] < ' ') {
Expand Down Expand Up @@ -660,6 +742,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: "));
Expand Down Expand Up @@ -776,16 +865,52 @@ 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 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);

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.
if (isnan(Z2)) {
Z1 = Z2;
}
if (G2orG3 == 2){
arc(X1, Y1, Z1, X2, Y2, Z2, centerX, centerY, sys.feedrate, CLOCKWISE);
}
Expand Down
5 changes: 4 additions & 1 deletion cnc_ctrl_v1/GCode.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ Copyright 2014-2017 Bar Smith*/
extern String readyCommandString; //next command queued up and ready to send
extern String gcodeLine; //The next individual line of gcode (for example G91 G01 X19 would be run as two lines)

extern int SpindlePowerControlPin;

void initGCode();
void gcodeExecuteLoop();
void readSerialCommands();
Expand All @@ -34,6 +36,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&);
Expand All @@ -44,7 +47,7 @@ void G4(const String&);
void G10(const String&);
void G38(const String&);
void setInchesToMillimetersConversion(float);
extern int SpindlePowerControlPin;

extern int ProbePin;
extern int FAKE_SERVO_STATE;

Expand Down
2 changes: 2 additions & 0 deletions cnc_ctrl_v1/Kinematics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,8 @@ void Kinematics::_inverse(float xTarget,float yTarget, float* aChainLength, flo

void Kinematics::_quadrilateralInverse(float xTarget,float yTarget, float* aChainLength, float* bChainLength){

//Confirm that the coordinates are on the wood
_verifyValidTarget(&xTarget, &yTarget); // OK
//coordinate shift to put (0,0) in the center of the plywood from the left sprocket
y = (halfHeight) + sysSettings.motorOffsetY - yTarget;
x = (sysSettings.distBetweenMotors/2.0) + xTarget;
Expand Down
3 changes: 2 additions & 1 deletion cnc_ctrl_v1/Kinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@
float _YOffsetEqn(const float& YPlus, const float& Denominator, const float& Psi);
void _MatSolv();
void _MyTrig();
float x = 0; //target router bit coordinates.
//target router bit coordinates.
float x = 0;
float y = 0;
float _xCordOfMotor;
float _yCordOfMotor;
Expand Down
2 changes: 1 addition & 1 deletion cnc_ctrl_v1/Maslow.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#define maslow_h

// Maslow Firmware Version tracking
#define VERSIONNUMBER 51.28
#define VERSIONNUMBER 51.29

// Define standard libraries used by maslow.
#include <avr/io.h>
Expand Down
Loading