Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
25 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
5cb104a
Merge Upstream Commits into Holey Firmware
krkeegan Aug 5, 2020
d9cfddd
Fix Missed Conflict
krkeegan Aug 5, 2020
ce31649
Fix Duplicate Init from Merge
krkeegan Aug 5, 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
c073f52
Update System.cpp
Orob-Maslow Sep 13, 2020
a00b492
Merge branch 'HoleySpindlePwm' into merge_upstream
Orob-Maslow Sep 13, 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
57 changes: 51 additions & 6 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,24 @@ 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);

}

long Axis::steps(){
Expand Down Expand Up @@ -225,8 +255,23 @@ void Axis::detachIfIdle(){

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

_timeLastMoved = millis();
_pidSetpoint = finalTarget/ *_mmPerRotation;
_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;
}
}

_pidSetpoint = finalTarget/ *_mmPerRotation;

}

Expand Down
8 changes: 8 additions & 0 deletions cnc_ctrl_v1/Config.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,11 +20,15 @@

// 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.
Expand Down Expand Up @@ -55,12 +59,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 +79,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
104 changes: 103 additions & 1 deletion 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 @@ -369,6 +370,51 @@ byte executeBcodeLine(const String& gcodeLine){
return STATUS_OK;
}

// 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.
Expand Down Expand Up @@ -398,7 +444,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){
/*

Expand Down Expand Up @@ -566,6 +622,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 +719,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 +842,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
1 change: 1 addition & 0 deletions cnc_ctrl_v1/GCode.h
Original file line number Diff line number Diff line change
Expand Up @@ -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&);
Expand Down
Loading