v1.1d: Tweaked interface a bit. Added realtime spindle speed and build option data. Minor bug fixes.
- Increment to v1.1d due to interface tweaks. - Based on GUI dev feedback, the toggle overrides report was removed and replace with showing “accessory state”. This shows a character if a particular accessory is enabled, like the spindle or flood coolant. These can be directly altered by the toggle overrides, so when they execute, a GUI will be able to observe the state altering as feedback. - Altered the real-time feed rate to show real-time spindle speed as well. It was an over-sight on my part. It’s needed because it’s hard to know what the current spindle speed is when overrides are altering it. Especially during something like a laser cutting job when its important to know how spindle speed overrides are effecting things. - Real-time spindle speed is not shown if VARIABLE_SPINDLE is disabled. The old real-time feed rate data field will show instead. - Compile-time option data is now included in another message immediately following the build info version string, starting with `[OPT:`. A character code follows the data type name with each indicating a particular option enabled or disabled. This will help immensely with debugging Grbl as well as help GUIs know exactly how Grbl was compiled. - These interface changes are detailed in the updated documentation. - Reduced the default planner buffer size from 17 to 16. Needed to free up some memory… - For increasing the serial TX buffer size from 90 to 104 bytes. The addition of real-time spindle speeds and accessory enable data required a bigger buffer. This is to ensure Grbl is performing at optimal levels. - Refactored parts of the spindle and coolant control code to make it more consistent to each other and how it was called. It was a little messy. The changes made it easier to track what each function call was doing based on what was calling it. - Created a couple of new get_state functions for the spindle and coolant. These are called by the accessory state report to look directly at the pin state, rather than track how it was set. This guarantees that the state is reported correctly. - Updated the g-code parser, parking motion, sleep mode, and spindle stop calls to refactored spindle and coolant code. - Added a compile-time option to enable homing individual axes, rather than having only the main homing cycle. The actual use case for this is pretty rare. It’s not recommended you enable this, unless you have a specific application for it. Otherwise, just alter the homing cycle itself. - Refactored the printFloat() function to not show a decimal point if there are no trailing values after it. For example, `1.` now shows `1`. - Fixed an issue regarding spindle speed overrides no being applied to blocks without motions. - Removed the toggle_ovr_mask system variable and replaced with spindle_stop_ovr system variable. Coolant toggles don’t need to be tracked. - Updated README
This commit is contained in:
parent
c8ac98d6e0
commit
ed790c9fa2
4
Makefile
4
Makefile
@ -44,10 +44,10 @@ FUSES = -U hfuse:w:0xd2:m -U lfuse:w:0xff:m
|
||||
AVRDUDE = avrdude $(PROGRAMMER) -p $(DEVICE) -B 10 -F
|
||||
|
||||
# Compile flags for avr-gcc v4.8.1. Does not produce -flto warnings.
|
||||
COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections
|
||||
# COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections
|
||||
|
||||
# Compile flags for avr-gcc v4.9.2 compatible with the IDE. Or if you don't care about the warnings.
|
||||
# COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections -flto
|
||||
COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections -flto
|
||||
|
||||
|
||||
OBJECTS = $(addprefix $(BUILDDIR)/,$(notdir $(SOURCE:.c=.o)))
|
||||
|
@ -7,7 +7,7 @@ _**This is the development branch for Grbl v1.1's upcoming release. Please keep
|
||||
|
||||
***
|
||||
|
||||
Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. This version of Grbl runs on an Arduino Uno.
|
||||
Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. This version of Grbl runs on an Arduino with a 328p processor (Uno, Duemilanove, Nano, Micro, etc).
|
||||
|
||||
The controller is written in highly optimized C utilizing every clever feature of the AVR-chips to achieve precise timing and asynchronous operation. It is able to maintain up to 30kHz of stable, jitter free control pulses.
|
||||
|
||||
@ -42,7 +42,7 @@ Grbl includes full acceleration management with look ahead. That means the contr
|
||||
|
||||
- **Sleep Mode** : Grbl may now be put to "sleep" via a `$SLP` command. This will disable everything, including the stepper drivers. Nice to have when you are leaving your machine unattended and want to power down everything automatically. Only a reset exits the sleep state.
|
||||
|
||||
- **Significant Interface Improvements**: Just this one time and done simultaneously with adding override data and controls, Grbl has tweaked the communication interface to make it easier for developers to write and maintain their GUIs. _NOTE: GUIs need to specifically update their code to be compatible with v1.1 and later._
|
||||
- **Significant Interface Improvements**: Tweaked to increase overall performance, include lots more real-time data, and to simplify maintaining and writing GUIs. Based on direct feedback from multiple GUI developers and bench performance testing. _NOTE: GUIs need to specifically update their code to be compatible with v1.1 and later._
|
||||
|
||||
- **New Status Reports**: To account for the additional override data, status reports have been tweaked to cram more data into it, while still being smaller than before. Documentation is included, outlining how it has been changed.
|
||||
- **Improved Error/Alarm Feedback** : All Grbl error and alarm messages have been changed to providing a code. Each code is associated with a specific problem, so users will know exactly what is wrong without having to guess. Documentation and an easy to parse CSV is included in the repo.
|
||||
|
16
doc/csv/build_option_codes_en_US.csv
Normal file
16
doc/csv/build_option_codes_en_US.csv
Normal file
@ -0,0 +1,16 @@
|
||||
"OPT: Code"," Build-Option Description","State"
|
||||
"V","Variable spindle","Enabled"
|
||||
"N","Line numbers","Enabled"
|
||||
"M","Mist coolant M7","Enabled"
|
||||
"C","CoreXY","Enabled"
|
||||
"P","Parking motion","Enabled"
|
||||
"Z","Homing force origin","Enabled"
|
||||
"H","Homing single axis commands","Enabled"
|
||||
"L","Two limit switches on axis","Enabled"
|
||||
"R","Classic status reporting","Enabled"
|
||||
"*","Restore all EEPROM command","Disabled"
|
||||
"$","Restore EEPROM `$` settings command","Disabled"
|
||||
"#","Restore EEPROM parameter data command","Disabled"
|
||||
"I","Build info write user string command","Disabled"
|
||||
"E","Force sync upon EEPROM write","Disabled"
|
||||
"W","Force sync upon work coordinate offset change","Disabled"
|
|
@ -1,3 +1,32 @@
|
||||
----------------
|
||||
Date: 2016-10-17
|
||||
Author: Will Winder
|
||||
Subject: Modify code CSV format. (#10)
|
||||
|
||||
- Wrap value in quotes to avoid issue with embedded commas. This occurs
|
||||
in one of the alarm codes.
|
||||
|
||||
- Change header row format to allow same parsing code as data rows.
|
||||
|
||||
----------------
|
||||
Date: 2016-10-12
|
||||
Author: chamnit
|
||||
Subject: Merge branch 'dev' into edge
|
||||
|
||||
|
||||
----------------
|
||||
Date: 2016-10-12
|
||||
Author: chamnit
|
||||
Subject: Added settings documentation. Very minor bug fix to step direction handling.
|
||||
|
||||
- Added v1.1 settings documentation to the markdown folder.
|
||||
|
||||
- Fixed a very minor bug in the step direction handling upon wakeup.
|
||||
The direction mask would temporarily go back to default mask for about
|
||||
a millisecond when moving in the same non-default direction. It did not
|
||||
effect Grbl behavior before, but fixed for consistency.
|
||||
|
||||
|
||||
----------------
|
||||
Date: 2016-10-12
|
||||
Author: Sonny Jeon
|
||||
|
@ -29,6 +29,8 @@ Grbl v1.1's interface protocol has been tweaked in the attempt to make GUI devel
|
||||
|
||||
- `[VER:]` : Indicates build info and string from a `$I` user query.
|
||||
|
||||
- `[OPT:]` : Indicates compile-time option info from a `$I` user query.
|
||||
|
||||
- `[echo:]` : Indicates an automated line echo from a pre-parsed string prior to g-code parsing. Enabled by config.h option.
|
||||
|
||||
- `>G54G20:ok` : The open chevron indicates startup line execution. The `:ok` suffix shows it executed correctly without adding an unmatched `ok` response on a new line.
|
||||
|
@ -16,7 +16,7 @@ In other words, both commands sent to Grbl and messages received from Grbl have
|
||||
The start up message always prints upon startup and after a reset. Whenever you see this message, this also means that Grbl has completed re-initializing all its systems, so everything starts out the same every time you use Grbl.
|
||||
|
||||
* `X.Xx` indicates the major version number, followed by a minor version letter. The major version number indicates the general release, while the letter simply indicates a feature update or addition from the preceding minor version letter.
|
||||
* Bug fix revisions are tracked by the build info version number, printed when an `$I` command is sent. These revisions don't update the version number and are given by date revised in year, month, and day, like so `20160820`.
|
||||
* Bug fix revisions are tracked by the build info version number, printed when an `$I` command is sent. These revisions don't update the version number and are given by date revised in year, month, and day, like so `20161014`.
|
||||
|
||||
#### Grbl `$` Help Message
|
||||
|
||||
@ -26,7 +26,7 @@ Every string Grbl receives is assumed to be a G-code block/line for it to execut
|
||||
[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H ~ ! ? ctrl-x]
|
||||
```
|
||||
|
||||
- _**NOTE:** Grbl v1.1's new override real-time commands are not included in the help message. They use the extended-ASCII character set, which are not easily type-able, and require a GUI that supports them. This is for two reasons: Establish enough characters for all of the overrides with extra for later growth, and prevent accidental keystrokes or characters in a g-code file from enacting an override inadvertently. _
|
||||
- _**NOTE:** Grbl v1.1's new override real-time commands are not included in the help message. They use the extended-ASCII character set, which are not easily type-able, and require a GUI that supports them. This is for two reasons: Establish enough characters for all of the overrides with extra for later growth, and prevent accidental keystrokes or characters in a g-code file from enacting an override inadvertently._
|
||||
|
||||
* Check out our [Configuring Grbl](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9) wiki page to find out what all of these commands mean and how to use them.
|
||||
|
||||
@ -44,7 +44,7 @@ Every G-code block sent to Grbl and Grbl `$` system command that is terminated w
|
||||
|
||||
* **`error:X`**: Something went wrong! Grbl did not recognize the command and did not execute anything inside that message. The `X` is given as a numeric error code to tell you exactly what happened. The table below decribes every one of them.
|
||||
|
||||
| ID | Error Code Description |
|
||||
| ID | Error Code Description |
|
||||
|:-------------:|----|
|
||||
| **`1`** | G-code words consist of a letter and a value. Letter was not found. |
|
||||
| **`2`** | Numeric value format is not valid or missing an expected value. |
|
||||
@ -153,8 +153,8 @@ $24=25.000
|
||||
$25=500.000
|
||||
$26=250
|
||||
$27=1.000
|
||||
$30=1000.
|
||||
$31=0.
|
||||
$30=1000
|
||||
$31=0
|
||||
$32=0
|
||||
$100=250.000
|
||||
$101=250.000
|
||||
@ -171,7 +171,7 @@ $132=200.000
|
||||
ok
|
||||
```
|
||||
|
||||
| `$x` Code | Setting Description, Units |
|
||||
| `$x` Code | Setting Description, Units |
|
||||
|:-------------:|----|
|
||||
| **`0`** | Step pulse time, microseconds |
|
||||
| **`1`** | Step idle delay, milliseconds |
|
||||
@ -289,12 +289,35 @@ Feedback messages provide non-critical information on what Grbl is doing, what i
|
||||
|
||||
- The `PRB:` probe parameter message includes an additional `:` and suffix value is a boolean. It denotes whether the last probe cycle was successful or not.
|
||||
|
||||
- `[VER:]` : Indicates build info and string from a `$I` user query. The build info message is shown below with a separate `ok` to confirm the `$I` was executed.
|
||||
- `[VER:]` and `[OPT:]`: Indicates build info data from a `$I` user query. These build info messages are followed by an `ok` to confirm the `$I` was executed, like so:
|
||||
|
||||
```
|
||||
[VER:v1.1a.20160923:]
|
||||
[VER:v1.1d.20161014:Some string]
|
||||
[OPT:VL]
|
||||
ok
|
||||
```
|
||||
- A string may appear after the `:` colon. It is a stored EEPROM string a user or OEM can place there for personal use or tracking purposes.
|
||||
|
||||
- The first line `[VER:]` contains the build version and date.
|
||||
- A string may appear after the second `:` colon. It is a stored EEPROM string a user via a `$I=line` command or OEM can place there for personal use or tracking purposes.
|
||||
- The `[OPT:]` line follows immediately after and contains character codes for compile-time options that were either enabled or disabled. The codes are defined below and a CSV file is also provided for quick parsing. This is generally only used for quickly diagnosing firmware bugs or compatibility issues.
|
||||
|
||||
| `OPT` Code | Setting Description, Units |
|
||||
|:-------------:|----|
|
||||
| **`V`** | Variable spindle enabled |
|
||||
| **`N`** | Line numbers enabled |
|
||||
| **`M`** | Mist coolant enabled |
|
||||
| **`C`** | CoreXY enabled |
|
||||
| **`P`** | Parking motion enabled |
|
||||
| **`Z`** | Homing force origin enabled |
|
||||
| **`H`** | Homing single axis enabled |
|
||||
| **`L`** | Two limit switches on axis enabled |
|
||||
| **`R`** | Classic status reporting enabled |
|
||||
| **`*`** | Restore all EEPROM disabled |
|
||||
| **`$`** | Restore EEPROM `$` settings disabled |
|
||||
| **`#`** | Restore EEPROM parameter data disabled |
|
||||
| **`I`** | Build info write user string disabled |
|
||||
| **`E`** | Force sync upon EEPROM write disabled |
|
||||
| **`W`** | Force sync upon work coordinate offset change disabled |
|
||||
|
||||
- `[echo:]` : Indicates an automated line echo from a command just prior to being parsed and executed. May be enabled only by a config.h option. Often used for debugging communication issues. A typical line echo message is shown below. A separate `ok` will eventually appear to confirm the line has been parsed and executed, but may not be immediate as with any line command containing motions.
|
||||
```
|
||||
@ -371,17 +394,12 @@ Feedback messages provide non-critical information on what Grbl is doing, what i
|
||||
|
||||
- Current sub-states are:
|
||||
|
||||
- `Hold:0` Hold complete. Ready to resume.
|
||||
|
||||
- `Hold:1` Hold in-progress. Reset will throw an alarm.
|
||||
|
||||
- `Door:0` Door closed. Ready to resume.
|
||||
|
||||
- `Door:1` Machine stopped. Door still ajar. Can't resume until closed.
|
||||
|
||||
- `Door:2` Door opened. Hold (or parking retract) in-progress. Reset will throw an alarm.
|
||||
|
||||
- `Door:3` Door closed and resuming. Restoring from park, if applicable. Reset will throw an alarm.
|
||||
- `Hold:0` Hold complete. Ready to resume.
|
||||
- `Hold:1` Hold in-progress. Reset will throw an alarm.
|
||||
- `Door:0` Door closed. Ready to resume.
|
||||
- `Door:1` Machine stopped. Door still ajar. Can't resume until closed.
|
||||
- `Door:2` Door opened. Hold (or parking retract) in-progress. Reset will throw an alarm.
|
||||
- `Door:3` Door closed and resuming. Restoring from park, if applicable. Reset will throw an alarm.
|
||||
|
||||
- This data field is always present as the first field.
|
||||
|
||||
@ -390,7 +408,6 @@ Feedback messages provide non-critical information on what Grbl is doing, what i
|
||||
- Depending on `$10` status report mask settings, position may be sent as either:
|
||||
|
||||
- `MPos:0.000,-10.000,5.000` machine position or
|
||||
|
||||
- `WPos:-2.500,0.000,11.000` work position
|
||||
|
||||
- Three position values are given in the order of X, Y, and Z. A fourth position value may exist in later versions for the A-axis.
|
||||
@ -413,15 +430,12 @@ Feedback messages provide non-critical information on what Grbl is doing, what i
|
||||
- This data field appears:
|
||||
|
||||
- In every 10 or 30 (configurable 1-255) status reports, depending on if Grbl is in a motion state or not.
|
||||
|
||||
- Immediately in the next report, if an offset value has changed.
|
||||
|
||||
- In the first report after a reset/power-cycle.
|
||||
|
||||
- This data field will not appear if:
|
||||
|
||||
- It is disabled in the config.h file. No `$` mask setting available.
|
||||
|
||||
- The refresh counter is in-between intermittent reports.
|
||||
|
||||
- **Buffer State:**
|
||||
@ -449,26 +463,26 @@ Feedback messages provide non-critical information on what Grbl is doing, what i
|
||||
- This data field will not appear if:
|
||||
|
||||
- It is disabled in the config.h file. No `$` mask setting available.
|
||||
|
||||
- The line number reporting not enabled in config.h. Different option to reporting data field.
|
||||
|
||||
- No line number or `N0` is passed with the g-code block.
|
||||
|
||||
- Grbl is homing, jogging, parking, or performing a system task/motion.
|
||||
|
||||
- There is no motion in the g-code block like a `G4P1` dwell. (May be fixed in later versions.)
|
||||
|
||||
- **Current Rate:**
|
||||
- **Current Feed and Speed:**
|
||||
|
||||
- `F:1000.` indicates current actual feed rate (speed) of the executing motion. Depending on machine max rate settings and acceleration, this value may not be the programmed rate.
|
||||
|
||||
- Value units, either in mm/min or inches/min, is dependent on the `$` report inches user setting.
|
||||
- There are two versions of this data field that Grbl may respond with.
|
||||
|
||||
- `F:500` contains real-time feed rate data as the value. This appears only when VARIABLE_SPINDLE is disabled in config.h, because spindle speed is not tracked in this mode.
|
||||
- `FS:500,8000` contains real-time feed rate, followed by spindle speed, data as the values. Note the `FS:`, rather than `F:`, data type name indicates spindle speed data is included.
|
||||
|
||||
- The current feed rate value is in mm/min or inches/min, depending on the `$` report inches user setting.
|
||||
- The second value is the current spindle speed in RPM
|
||||
|
||||
- These values will often not be the programmed feed rate or spindle speed, because several situations can alter or limit them. For example, overrides directly scale the programmed values to a different running value, while machine settings, acceleration profiles, and even the direction traveled can also limit rates to maximum values allowable.
|
||||
|
||||
- As a operational note, reported rate is typically 30-50 msec behind actual position reported.
|
||||
|
||||
- This data field will not appear if:
|
||||
|
||||
- It is disabled in the config.h file. No `$` mask setting available.
|
||||
- This data field will always appear, unless it was explicitly disabled in the config.h file.
|
||||
|
||||
- **Input Pin State:**
|
||||
|
||||
@ -479,13 +493,9 @@ Feedback messages provide non-critical information on what Grbl is doing, what i
|
||||
- Each letter of `XYZPDHRS` denotes a particular 'triggered' input pin.
|
||||
|
||||
- `X Y Z` XYZ limit pins, respectively
|
||||
|
||||
- `P` the probe pin.
|
||||
|
||||
- `D H R S` the door, hold, soft-reset, and cycle-start pins, respectively.
|
||||
|
||||
- Example: `Pn:PZ` indicates the probe and z-limit pins are 'triggered'.
|
||||
|
||||
- Note: `A` may be added in later versions for an A-axis limit pin.
|
||||
|
||||
- Assume input pin letters are presented in no particular order.
|
||||
@ -495,58 +505,52 @@ Feedback messages provide non-critical information on what Grbl is doing, what i
|
||||
- This data field will not appear if:
|
||||
|
||||
- It is disabled in the config.h file. No `$` mask setting available.
|
||||
|
||||
- No input pins are detected as triggered.
|
||||
|
||||
- **Override Values:**
|
||||
|
||||
- `Ov:100,100,100` indicates current override values in percent of programmed values for feed, rapids, and spindle speed, respectively.
|
||||
|
||||
- Override maximum, minimum, and increment sizes are all configurable within config.h. Assume that a user or OEM will alter these based on customized use-cases. Recommend not hard-coding these values into a GUI, but rather just show the actual override values and generic increment buttons.
|
||||
|
||||
- Override values don't change often during a job once set and only requires intermittent refreshing. This data field appears:
|
||||
|
||||
- After 10 or 20 (configurable 1-255) status reports, depending on is in a motion state or not.
|
||||
|
||||
- If an override value has changed, this data field will appear immediately in the next report. However, if `WCO:` is present, this data field will be delayed one report.
|
||||
|
||||
- In the second report after a reset/power-cycle.
|
||||
|
||||
- This data field will not appear if:
|
||||
|
||||
- It is disabled in the config.h file. No `$` mask setting available.
|
||||
|
||||
- The override refresh counter is in-between intermittent reports.
|
||||
|
||||
- `WCO:` exists in current report during refresh. Automatically set to try again on next report.
|
||||
|
||||
- **Toggle Overrides:**
|
||||
- **Accessory State:**
|
||||
|
||||
- `T:SFM` indicates a toggle override is in effect or has been commanded.
|
||||
- `A:SFM` indicates the current state of accessory machine components, such as the spindle and coolant.
|
||||
|
||||
- Like the pin state field, each letter denotes a particular toggle override.
|
||||
|
||||
- `S` indicates the spindle stop toggle override is in effect. It will appear as long as the spindle stop override is active.
|
||||
|
||||
- `F` indicates the flood coolant toggle override was activated. It will only appear once after it has executed the coolant state change.
|
||||
|
||||
- `M` indicates the mist coolant toggle override was activated, if mist coolant is enabled via config.h. It will only appear once after it has executed the coolant state change.
|
||||
|
||||
- Assume toggle override letters are presented in no particular order.
|
||||
|
||||
- One or more active toggle override letter(s) will always be present with a `T:` data field.
|
||||
- Due to the new toggle overrides, these machine components may not be running according to the g-code program. This data is provided to ensure the user knows exactly what Grbl is doing at any given time.
|
||||
|
||||
- Each letter after `A:` denotes a particular state. When it appears, the state is enabled. When it does not appear, the state is disabled.
|
||||
|
||||
- `S` indicates spindle is enabled in the CW direction. This does not appear with `C`.
|
||||
- `C` indicates spindle is enabled in the CCW direction. This does not appear with `S`.
|
||||
- `F` indicates flood coolant is enabled.
|
||||
- `M` indicates mist coolant is enabled.
|
||||
|
||||
- Assume accessory state letters are presented in no particular order.
|
||||
|
||||
- This data field appears:
|
||||
|
||||
- If a toggle override is active or has recently executed and only when the override values field is also present (see override value field rules).
|
||||
- When any accessory state is enabled.
|
||||
- Only with the override values field in the same message. Any accessory state change will trigger the accessory state and override values fields to be shown on the next report.
|
||||
|
||||
- This data field will not appear if:
|
||||
|
||||
- If no toggle override is active or has been executed.
|
||||
|
||||
- It is disabled in the config.h file. No `$` mask setting available.
|
||||
|
||||
- If override refresh counter is in-between intermittent reports.
|
||||
|
||||
- `WCO:` exists in current report during refresh. Automatically set to try again on next report.
|
||||
- No accessory state is active.
|
||||
- It is disabled in the config.h file. No `$` mask setting available.
|
||||
- If override refresh counter is in-between intermittent reports.
|
||||
- `WCO:` exists in current report during refresh. Automatically set to try again on next report.
|
||||
|
||||
|
||||
-------
|
||||
|
@ -17,7 +17,7 @@ Once connected
|
||||
you should get the Grbl-prompt, which looks like this:
|
||||
|
||||
```
|
||||
Grbl 1.1c ['$' for help]
|
||||
Grbl 1.1d ['$' for help]
|
||||
```
|
||||
|
||||
Type $ and press enter to have Grbl print a help message. You should not see any local echo of the $ and enter. Grbl should respond with:
|
||||
@ -354,7 +354,7 @@ For example, say that you want to use your first startup block `$N0` to set your
|
||||
Once you have a startup block stored in Grbl's EEPROM, everytime you startup or reset you will see your startup block printed back to you, starting with an open-chevron `>`, and a `:ok` response from Grbl to indicate if it ran okay. So for the previous example, you'll see:
|
||||
|
||||
```
|
||||
Grbl 1.1c ['$' for help]
|
||||
Grbl 1.1d ['$' for help]
|
||||
>G20G54G17:ok
|
||||
|
||||
```
|
||||
|
@ -106,11 +106,23 @@
|
||||
#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS)) // OPTIONAL: Then move X,Y at the same time.
|
||||
// #define HOMING_CYCLE_2 // OPTIONAL: Uncomment and add axes mask to enable
|
||||
|
||||
// NOTE: The following are two examples to setup homing for 2-axis machines.
|
||||
// #define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS)) // NOT COMPATIBLE WITH COREXY: Homes both X-Y in one cycle.
|
||||
|
||||
// #define HOMING_CYCLE_0 (1<<X_AXIS) // COREXY COMPATIBLE: First home X
|
||||
// #define HOMING_CYCLE_1 (1<<Y_AXIS) // COREXY COMPATIBLE: Then home Y
|
||||
|
||||
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
||||
// This help in preventing overshoot and should improve repeatability. This value should be one or
|
||||
// greater.
|
||||
#define N_HOMING_LOCATE_CYCLE 1 // Integer (1-128)
|
||||
|
||||
// Enables single axis homing commands. $HX, $HY, and $HZ for X, Y, and Z-axis homing. The full homing
|
||||
// cycle is still invoked by the $H command. This is disabled by default. It's here only to address
|
||||
// users that need to switch between a two-axis and three-axis machine. This is actually very rare.
|
||||
// If you have a two-axis machine, DON'T USE THIS. Instead, just alter the homing cycle for two-axes.
|
||||
// #define HOMING_SINGLE_AXIS_COMMANDS // Default disabled. Uncomment to enable.
|
||||
|
||||
// After homing, Grbl will set by default the entire machine space into negative space, as is typical
|
||||
// for professional CNC machines, regardless of where the limit switches are located. Uncomment this
|
||||
// define to force Grbl to always set the machine origin at the homed location despite switch orientation.
|
||||
@ -262,7 +274,7 @@
|
||||
// situation demands it, but be aware GUIs may depend on this data. If disabled, it may not be compatible.
|
||||
#define REPORT_FIELD_BUFFER_STATE // Default enabled. Comment to disable.
|
||||
#define REPORT_FIELD_PIN_STATE // Default enabled. Comment to disable.
|
||||
#define REPORT_FIELD_CURRENT_RATE // Default enabled. Comment to disable.
|
||||
#define REPORT_FIELD_CURRENT_FEED_SPEED // Default enabled. Comment to disable.
|
||||
#define REPORT_FIELD_WORK_COORD_OFFSET // Default enabled. Comment to disable.
|
||||
#define REPORT_FIELD_OVERRIDES // Default enabled. Comment to disable.
|
||||
#define REPORT_FIELD_LINE_NUMBERS // Default enabled. Comment to disable.
|
||||
@ -420,7 +432,7 @@
|
||||
// available RAM, like when re-compiling for a Mega2560. Or decrease if the Arduino begins to
|
||||
// crash due to the lack of available RAM or if the CPU is having trouble keeping up with planning
|
||||
// new incoming motions as they are executed.
|
||||
// #define BLOCK_BUFFER_SIZE 17 // Uncomment to override default in planner.h.
|
||||
// #define BLOCK_BUFFER_SIZE 16 // Uncomment to override default in planner.h.
|
||||
|
||||
// Governs the size of the intermediary step segment buffer between the step execution algorithm
|
||||
// and the planner blocks. Each segment is set of steps executed at a constant velocity over a
|
||||
@ -451,7 +463,7 @@
|
||||
// around 90-100 characters. As long as the serial TX buffer doesn't get continually maxed, Grbl
|
||||
// will continue operating efficiently. Size the TX buffer around the size of a worst-case report.
|
||||
// #define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h
|
||||
// #define TX_BUFFER_SIZE 90 // (1-254)
|
||||
// #define TX_BUFFER_SIZE 100 // (1-254)
|
||||
|
||||
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets
|
||||
// the position to the probe target, when enabled sets the position to the start position.
|
||||
|
@ -27,47 +27,95 @@ void coolant_init()
|
||||
#ifdef ENABLE_M7
|
||||
COOLANT_MIST_DDR |= (1 << COOLANT_MIST_BIT);
|
||||
#endif
|
||||
coolant_set_state(COOLANT_DISABLE);
|
||||
coolant_stop();
|
||||
}
|
||||
|
||||
|
||||
void coolant_set_state(uint8_t mode)
|
||||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
uint8_t coolant_get_state()
|
||||
{
|
||||
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
|
||||
#else
|
||||
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
|
||||
#endif
|
||||
} else {
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
|
||||
#else
|
||||
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
|
||||
#endif
|
||||
uint8_t cl_state = COOLANT_STATE_DISABLE;
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if (bit_isfalse(COOLANT_FLOOD_PORT,(1 << COOLANT_FLOOD_BIT))) {
|
||||
#else
|
||||
if (bit_istrue(COOLANT_FLOOD_PORT,(1 << COOLANT_FLOOD_BIT))) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
}
|
||||
#ifdef ENABLE_M7
|
||||
if (mode & COOLANT_MIST_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
|
||||
#else
|
||||
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
|
||||
#endif
|
||||
} else {
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
|
||||
#else
|
||||
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
|
||||
#endif
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
if (bit_isfalse(COOLANT_MIST_PORT,(1 << COOLANT_MIST_BIT))) {
|
||||
#else
|
||||
if (bit_istrue(COOLANT_MIST_PORT,(1 << COOLANT_MIST_BIT))) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_MIST;
|
||||
}
|
||||
#endif
|
||||
return(cl_state);
|
||||
}
|
||||
|
||||
|
||||
// Directly called by coolant_init(), coolant_set_state(), and mc_reset(), which can be at
|
||||
// an interrupt-level. No report flag set, but only called by routines that don't need it.
|
||||
void coolant_stop()
|
||||
{
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
|
||||
#else
|
||||
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
|
||||
#endif
|
||||
#ifdef ENABLE_M7
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
|
||||
#else
|
||||
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
void coolant_run(uint8_t mode)
|
||||
// Main program only. Immediately sets flood coolant running state and also mist coolant,
|
||||
// if enabled. Also sets a flag to report an update to a coolant state.
|
||||
// Called by coolant toggle override, parking restore, parking retract, sleep mode, g-code
|
||||
// parser program end, and g-code parser coolant_sync().
|
||||
void coolant_set_state(uint8_t mode)
|
||||
{
|
||||
if (sys.abort) { return; } // Block during abort.
|
||||
|
||||
if (mode == COOLANT_DISABLE) {
|
||||
|
||||
coolant_stop();
|
||||
|
||||
} else {
|
||||
|
||||
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
|
||||
#else
|
||||
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef ENABLE_M7
|
||||
if (mode & COOLANT_MIST_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
|
||||
#else
|
||||
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to report change immediately
|
||||
}
|
||||
|
||||
|
||||
// G-code parser entry-point for setting coolant state. Forces a planner buffer sync and bails
|
||||
// if an abort or check-mode is active.
|
||||
void coolant_sync(uint8_t mode)
|
||||
{
|
||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
||||
if (sys.abort) { return; } // Block during abort.
|
||||
coolant_set_state(mode);
|
||||
}
|
||||
|
@ -21,9 +21,27 @@
|
||||
#ifndef coolant_control_h
|
||||
#define coolant_control_h
|
||||
|
||||
#define COOLANT_NO_SYNC false
|
||||
#define COOLANT_FORCE_SYNC true
|
||||
|
||||
#define COOLANT_STATE_DISABLE 0 // Must be zero
|
||||
#define COOLANT_STATE_FLOOD bit(0)
|
||||
#define COOLANT_STATE_MIST bit(1)
|
||||
|
||||
|
||||
// Initializes coolant control pins.
|
||||
void coolant_init();
|
||||
|
||||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
uint8_t coolant_get_state();
|
||||
|
||||
// Immediately disables coolant pins.
|
||||
void coolant_stop();
|
||||
|
||||
// Sets the coolant pins according to state specified.
|
||||
void coolant_set_state(uint8_t mode);
|
||||
void coolant_run(uint8_t mode);
|
||||
|
||||
// G-code parser entry-point for setting coolant states. Checks for and executes additional conditions.
|
||||
void coolant_sync(uint8_t mode);
|
||||
|
||||
#endif
|
||||
|
@ -124,8 +124,8 @@
|
||||
|
||||
// Variable spindle configuration below. Do not change unless you know what you are doing.
|
||||
// NOTE: Only used when variable spindle is enabled.
|
||||
#define SPINDLE_PWM_MAX_VALUE 255.0 // Don't change. 328p fast PWM mode fixes top value as 255.
|
||||
#define SPINDLE_PWM_OFF_VALUE 0.0
|
||||
#define SPINDLE_PWM_MAX_VALUE 255 // Don't change. 328p fast PWM mode fixes top value as 255.
|
||||
#define SPINDLE_PWM_OFF_VALUE 0
|
||||
#define SPINDLE_TCCRA_REGISTER TCCR2A
|
||||
#define SPINDLE_TCCRB_REGISTER TCCR2B
|
||||
#define SPINDLE_OCR_REGISTER OCR2A
|
||||
@ -137,7 +137,6 @@
|
||||
// #define SPINDLE_TCCRB_INIT_MASK ((1<<CS21) | (1<<CS20)) // 1/32 prescaler -> 1.96kHz
|
||||
#define SPINDLE_TCCRB_INIT_MASK (1<<CS22) // 1/64 prescaler -> 0.98kHz
|
||||
|
||||
|
||||
// NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings.
|
||||
#define SPINDLE_PWM_DDR DDRB
|
||||
#define SPINDLE_PWM_PORT PORTB
|
||||
|
16
grbl/gcode.c
16
grbl/gcode.c
@ -904,14 +904,14 @@ uint8_t gc_execute_line(char *line)
|
||||
if ( bit_istrue(settings.flags, BITFLAG_LASER_MODE) ) {
|
||||
// Do not stop motion if in laser mode and a G1, G2, or G3 motion is being executed.
|
||||
if (!( (axis_command == AXIS_COMMAND_MOTION_MODE) && ((gc_block.modal.motion == MOTION_MODE_LINEAR ) || (gc_block.modal.motion == MOTION_MODE_CW_ARC) || (gc_block.modal.motion == MOTION_MODE_CCW_ARC)) ) ) {
|
||||
spindle_run(gc_state.modal.spindle, gc_block.values.s);
|
||||
spindle_sync(gc_state.modal.spindle, gc_block.values.s);
|
||||
}
|
||||
} else {
|
||||
spindle_run(gc_state.modal.spindle, gc_block.values.s);
|
||||
spindle_sync(gc_state.modal.spindle, gc_block.values.s);
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) { spindle_run(gc_state.modal.spindle, gc_block.values.s); }
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) { spindle_sync(gc_state.modal.spindle); }
|
||||
#endif
|
||||
gc_state.spindle_speed = gc_block.values.s;
|
||||
}
|
||||
@ -925,7 +925,11 @@ uint8_t gc_execute_line(char *line)
|
||||
// [7. Spindle control ]:
|
||||
if (gc_state.modal.spindle != gc_block.modal.spindle) {
|
||||
// Update spindle control and apply spindle speed when enabling it in this block.
|
||||
spindle_run(gc_block.modal.spindle, gc_state.spindle_speed);
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
spindle_sync(gc_block.modal.spindle, gc_state.spindle_speed);
|
||||
#else
|
||||
spindle_sync(gc_block.modal.spindle);
|
||||
#endif
|
||||
gc_state.modal.spindle = gc_block.modal.spindle;
|
||||
}
|
||||
pl_data->condition |= gc_state.modal.spindle; // Set condition flag for planner use.
|
||||
@ -934,7 +938,7 @@ uint8_t gc_execute_line(char *line)
|
||||
if (gc_state.modal.coolant != gc_block.modal.coolant) {
|
||||
// NOTE: Coolant M-codes are modal. Only one command per line is allowed. But, multiple states
|
||||
// can exist at the same time, while coolant disable clears all states.
|
||||
coolant_run(gc_block.modal.coolant);
|
||||
coolant_sync(gc_block.modal.coolant);
|
||||
if (gc_block.modal.coolant == COOLANT_DISABLE) { gc_state.modal.coolant = COOLANT_DISABLE; }
|
||||
else { gc_state.modal.coolant |= gc_block.modal.coolant; }
|
||||
}
|
||||
@ -1095,7 +1099,7 @@ uint8_t gc_execute_line(char *line)
|
||||
if (sys.state != STATE_CHECK_MODE) {
|
||||
if (!(settings_read_coord_data(gc_state.modal.coord_select,gc_state.coord_system))) { FAIL(STATUS_SETTING_READ_FAIL); }
|
||||
system_flag_wco_change(); // Set to refresh immediately just in case something altered.
|
||||
spindle_stop();
|
||||
spindle_set_state(SPINDLE_DISABLE,0.0);
|
||||
coolant_set_state(COOLANT_DISABLE);
|
||||
}
|
||||
report_feedback_message(MESSAGE_PROGRAM_END);
|
||||
|
@ -22,8 +22,8 @@
|
||||
#define grbl_h
|
||||
|
||||
// Grbl versioning system
|
||||
#define GRBL_VERSION "1.1c"
|
||||
#define GRBL_VERSION_BUILD "20161012"
|
||||
#define GRBL_VERSION "1.1d"
|
||||
#define GRBL_VERSION_BUILD "20161017"
|
||||
|
||||
// Define standard libraries used by Grbl.
|
||||
#include <avr/io.h>
|
||||
|
@ -81,7 +81,7 @@ int main(void)
|
||||
sys.f_override = DEFAULT_FEED_OVERRIDE;
|
||||
sys.r_override = DEFAULT_RAPID_OVERRIDE;
|
||||
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE;
|
||||
sys.toggle_ovr_mask = 0;
|
||||
sys.spindle_stop_ovr = 0;
|
||||
sys.report_wco_counter = REPORT_WCO_REFRESH_BUSY_COUNT; // Set to include in first report.
|
||||
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to include in first report.
|
||||
|
||||
|
@ -193,7 +193,7 @@ void mc_dwell(float seconds)
|
||||
// Perform homing cycle to locate and set machine zero. Only '$H' executes this command.
|
||||
// NOTE: There should be no motions in the buffer and Grbl must be in an idle state before
|
||||
// executing the homing cycle. This prevents incorrect buffered plans after homing.
|
||||
void mc_homing_cycle()
|
||||
void mc_homing_cycle(uint8_t cycle_mask)
|
||||
{
|
||||
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
|
||||
// with machines with limits wired on both ends of travel to one limit pin.
|
||||
@ -210,15 +210,21 @@ void mc_homing_cycle()
|
||||
|
||||
// -------------------------------------------------------------------------------------
|
||||
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
||||
|
||||
// Search to engage all axes limit switches at faster homing seek rate.
|
||||
limits_go_home(HOMING_CYCLE_0); // Homing cycle 0
|
||||
#ifdef HOMING_CYCLE_1
|
||||
limits_go_home(HOMING_CYCLE_1); // Homing cycle 1
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_2
|
||||
limits_go_home(HOMING_CYCLE_2); // Homing cycle 2
|
||||
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
if (cycle_mask) { limits_go_home(cycle_mask); } // Perform homing cycle based on mask.
|
||||
else
|
||||
#endif
|
||||
{
|
||||
// Search to engage all axes limit switches at faster homing seek rate.
|
||||
limits_go_home(HOMING_CYCLE_0); // Homing cycle 0
|
||||
#ifdef HOMING_CYCLE_1
|
||||
limits_go_home(HOMING_CYCLE_1); // Homing cycle 1
|
||||
#endif
|
||||
#ifdef HOMING_CYCLE_2
|
||||
limits_go_home(HOMING_CYCLE_2); // Homing cycle 2
|
||||
#endif
|
||||
}
|
||||
|
||||
protocol_execute_realtime(); // Check for reset and set system abort.
|
||||
if (sys.abort) { return; } // Did not complete. Alarm state set by mc_alarm.
|
||||
@ -340,7 +346,7 @@ void mc_reset()
|
||||
|
||||
// Kill spindle and coolant.
|
||||
spindle_stop();
|
||||
coolant_set_state(COOLANT_DISABLE);
|
||||
coolant_stop();
|
||||
|
||||
// Kill steppers only if in any motion state, i.e. cycle, actively holding, or homing.
|
||||
// NOTE: If steppers are kept enabled via the step idle delay setting, this also keeps
|
||||
|
@ -27,6 +27,12 @@
|
||||
#define HOMING_CYCLE_LINE_NUMBER 0
|
||||
#define PARKING_MOTION_LINE_NUMBER 0
|
||||
|
||||
#define HOMING_CYCLE_ALL 0 // Must be zero.
|
||||
#define HOMING_CYCLE_X bit(X_AXIS)
|
||||
#define HOMING_CYCLE_Y bit(Y_AXIS)
|
||||
#define HOMING_CYCLE_Z bit(Z_AXIS)
|
||||
|
||||
|
||||
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
||||
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
|
||||
// (1 minute)/feed_rate time.
|
||||
@ -43,7 +49,7 @@ void mc_arc(float *target, plan_line_data_t *pl_data, float *position, float *of
|
||||
void mc_dwell(float seconds);
|
||||
|
||||
// Perform homing cycle to locate machine zero. Requires limit switches.
|
||||
void mc_homing_cycle();
|
||||
void mc_homing_cycle(uint8_t cycle_mask);
|
||||
|
||||
// Perform tool length probe cycle. Requires probe switch.
|
||||
uint8_t mc_probe_cycle(float *target, plan_line_data_t *pl_data, uint8_t is_probe_away, uint8_t is_no_error);
|
||||
|
@ -28,7 +28,7 @@
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
#define BLOCK_BUFFER_SIZE 15
|
||||
#else
|
||||
#define BLOCK_BUFFER_SIZE 17
|
||||
#define BLOCK_BUFFER_SIZE 16
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
@ -149,9 +149,7 @@ void printFloat(float n, uint8_t decimal_places)
|
||||
unsigned char buf[13];
|
||||
uint8_t i = 0;
|
||||
uint32_t a = (long)n;
|
||||
buf[decimal_places] = '.'; // Place decimal point, even if decimal places are zero.
|
||||
while(a > 0) {
|
||||
if (i == decimal_places) { i++; } // Skip decimal point location
|
||||
buf[i++] = (a % 10) + '0'; // Get digit
|
||||
a /= 10;
|
||||
}
|
||||
@ -159,13 +157,14 @@ void printFloat(float n, uint8_t decimal_places)
|
||||
buf[i++] = '0'; // Fill in zeros to decimal point for (n < 1)
|
||||
}
|
||||
if (i == decimal_places) { // Fill in leading zero, if needed.
|
||||
i++;
|
||||
buf[i++] = '0';
|
||||
}
|
||||
|
||||
// Print the generated string.
|
||||
for (; i > 0; i--)
|
||||
for (; i > 0; i--) {
|
||||
if (i == decimal_places) { serial_write('.'); } // Insert decimal point in right place.
|
||||
serial_write(buf[i-1]);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -347,8 +347,8 @@ void protocol_exec_rt_system()
|
||||
}
|
||||
// Cycle start only when IDLE or when a hold is complete and ready to resume.
|
||||
if ((sys.state == STATE_IDLE) || ((sys.state & STATE_HOLD) && (sys.suspend & SUSPEND_HOLD_COMPLETE))) {
|
||||
if (sys.state == STATE_HOLD && (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK)) {
|
||||
sys.toggle_ovr_mask |= TOGGLE_OVR_STOP_RESTORE_CYCLE; // Set to restore in suspend routine and cycle start after.
|
||||
if (sys.state == STATE_HOLD && sys.spindle_stop_ovr) {
|
||||
sys.spindle_stop_ovr |= SPINDLE_STOP_OVR_RESTORE_CYCLE; // Set to restore in suspend routine and cycle start after.
|
||||
} else {
|
||||
// Start cycle only if queued motions exist in planner buffer and the motion is not canceled.
|
||||
sys.step_control = STEP_CONTROL_NORMAL_OP; // Restore step control to normal operation
|
||||
@ -450,17 +450,17 @@ void protocol_exec_rt_system()
|
||||
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to report change immediately
|
||||
}
|
||||
|
||||
uint8_t last_toggle_ovr_mask = sys.toggle_ovr_mask;
|
||||
if (rt_exec & EXEC_SPINDLE_OVR_STOP) {
|
||||
// Toggle allowed only while in HOLD state.
|
||||
// Spindle stop override allowed only while in HOLD state.
|
||||
// NOTE: Report counters are set in spindle_set_state() when spindle stop is executed.
|
||||
if (sys.state == STATE_HOLD) {
|
||||
if (!(last_toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK)) { last_toggle_ovr_mask |= TOGGLE_OVR_STOP_INITIATE; }
|
||||
else if (last_toggle_ovr_mask & TOGGLE_OVR_STOP_ENABLED) { last_toggle_ovr_mask |= TOGGLE_OVR_STOP_RESTORE; }
|
||||
if (!(sys.spindle_stop_ovr)) { sys.spindle_stop_ovr = SPINDLE_STOP_OVR_INITIATE; }
|
||||
else if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_ENABLED) { sys.spindle_stop_ovr |= SPINDLE_STOP_OVR_RESTORE; }
|
||||
}
|
||||
}
|
||||
|
||||
// NOTE: Since coolant state always performs a planner sync whenever it changes, g-code parser
|
||||
// state can be implicitly determine current run state at the beginning of the planner.
|
||||
// NOTE: Since coolant state always performs a planner sync whenever it changes, the current
|
||||
// run state can be determined by checking the parser state.
|
||||
if (rt_exec & (EXEC_COOLANT_FLOOD_OVR_TOGGLE | EXEC_COOLANT_MIST_OVR_TOGGLE)) {
|
||||
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOLD))) {
|
||||
uint8_t coolant_state = gc_state.modal.coolant;
|
||||
@ -468,28 +468,19 @@ void protocol_exec_rt_system()
|
||||
if (rt_exec & EXEC_COOLANT_MIST_OVR_TOGGLE) {
|
||||
if (coolant_state & COOLANT_MIST_ENABLE) { bit_false(coolant_state,COOLANT_MIST_ENABLE); }
|
||||
else { coolant_state |= COOLANT_MIST_ENABLE; }
|
||||
last_toggle_ovr_mask |= TOGGLE_OVR_MIST_COOLANT;
|
||||
}
|
||||
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE) {
|
||||
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
|
||||
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
|
||||
last_toggle_ovr_mask |= TOGGLE_OVR_FLOOD_COOLANT;
|
||||
}
|
||||
#else
|
||||
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
|
||||
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
|
||||
last_toggle_ovr_mask |= TOGGLE_OVR_FLOOD_COOLANT;
|
||||
#endif
|
||||
coolant_set_state(coolant_state);
|
||||
coolant_set_state(coolant_state); // Report counter set in coolant_set_state().
|
||||
gc_state.modal.coolant = coolant_state;
|
||||
}
|
||||
}
|
||||
|
||||
if (last_toggle_ovr_mask != sys.toggle_ovr_mask) {
|
||||
sys.toggle_ovr_mask = last_toggle_ovr_mask;
|
||||
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to report change immediately
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#ifdef DEBUG
|
||||
@ -540,7 +531,6 @@ static void protocol_exec_rt_suspend()
|
||||
restore_spindle_speed = block->spindle_speed;
|
||||
}
|
||||
#else
|
||||
float restore_spindle_speed = 0.0; // Without variable spindle, this value is unused.
|
||||
if (block == NULL) { restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant); }
|
||||
else { restore_condition = block->condition; }
|
||||
#endif
|
||||
@ -560,12 +550,12 @@ static void protocol_exec_rt_suspend()
|
||||
if (bit_isfalse(sys.suspend,SUSPEND_RETRACT_COMPLETE)) {
|
||||
|
||||
// Ensure any prior spindle stop override is disabled at start of safety door routine.
|
||||
bit_false(sys.toggle_ovr_mask,TOGGLE_OVR_STOP_ACTIVE_MASK);
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED;
|
||||
|
||||
#ifndef PARKING_ENABLE
|
||||
|
||||
spindle_stop(); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
spindle_set_state(SPINDLE_DISABLE,0.0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE);; // De-energize
|
||||
|
||||
#else
|
||||
|
||||
@ -592,7 +582,7 @@ static void protocol_exec_rt_suspend()
|
||||
mc_parking_motion(parking_target, pl_data);
|
||||
}
|
||||
|
||||
spindle_stop(); // De-energize
|
||||
spindle_set_state(SPINDLE_DISABLE,0.0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
|
||||
// Execute fast parking retract motion to parking target location.
|
||||
@ -606,8 +596,8 @@ static void protocol_exec_rt_suspend()
|
||||
|
||||
// Parking motion not possible. Just disable the spindle and coolant.
|
||||
// NOTE: Laser mode does not start a parking motion to ensure the laser stops immediately.
|
||||
spindle_stop(); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
spindle_set_state(SPINDLE_DISABLE,0.0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE);; // De-energize
|
||||
|
||||
}
|
||||
|
||||
@ -622,7 +612,7 @@ static void protocol_exec_rt_suspend()
|
||||
if (sys.state == STATE_SLEEP) {
|
||||
report_feedback_message(MESSAGE_SLEEP_MODE);
|
||||
// Spindle and coolant should already be stopped, but do it again just to be sure.
|
||||
spindle_stop(); // De-energize
|
||||
spindle_set_state(SPINDLE_DISABLE,0.0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
st_go_idle(); // Disable steppers
|
||||
while (!(sys.abort)) { protocol_exec_rt_system(); } // Do nothing until reset.
|
||||
@ -660,7 +650,11 @@ static void protocol_exec_rt_suspend()
|
||||
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
} else {
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||
#else
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)));
|
||||
#endif
|
||||
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||
}
|
||||
}
|
||||
@ -701,15 +695,16 @@ static void protocol_exec_rt_suspend()
|
||||
|
||||
// Feed hold manager. Controls spindle stop override states.
|
||||
// NOTE: Hold ensured as completed by condition check at the beginning of suspend routine.
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_INITIATE) { // Handles beginning of spindle stop
|
||||
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_INITIATE) { // Handles beginning of spindle stop
|
||||
|
||||
bit_false(sys.toggle_ovr_mask,TOGGLE_OVR_STOP_ACTIVE_MASK); // Clear stop override state
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||
spindle_stop(); // De-energize
|
||||
sys.toggle_ovr_mask |= TOGGLE_OVR_STOP_ENABLED; // Set stop override state to enabled, if de-energized.
|
||||
spindle_set_state(SPINDLE_DISABLE,0.0); // De-energize
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_ENABLED; // Set stop override state to enabled, if de-energized.
|
||||
} else {
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
|
||||
}
|
||||
|
||||
} else if (sys.toggle_ovr_mask & (TOGGLE_OVR_STOP_RESTORE | TOGGLE_OVR_STOP_RESTORE_CYCLE)) { // Handles restoring of spindle state
|
||||
} else if (sys.spindle_stop_ovr & (SPINDLE_STOP_OVR_RESTORE | SPINDLE_STOP_OVR_RESTORE_CYCLE)) { // Handles restoring of spindle state
|
||||
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||
report_feedback_message(MESSAGE_SPINDLE_RESTORE);
|
||||
@ -717,14 +712,18 @@ static void protocol_exec_rt_suspend()
|
||||
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
} else {
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||
#else
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)));
|
||||
#endif
|
||||
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||
}
|
||||
}
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_RESTORE_CYCLE) {
|
||||
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_RESTORE_CYCLE) {
|
||||
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
|
||||
}
|
||||
bit_false(sys.toggle_ovr_mask,TOGGLE_OVR_STOP_ACTIVE_MASK); // Clear stop override state
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
|
||||
|
||||
}
|
||||
|
||||
|
123
grbl/report.c
123
grbl/report.c
@ -527,6 +527,57 @@ void report_build_info(char *line)
|
||||
printPgmString(PSTR("[VER:" GRBL_VERSION "." GRBL_VERSION_BUILD ":"));
|
||||
printString(line);
|
||||
report_util_feedback_line_feed();
|
||||
printPgmString(PSTR("[OPT:")); // Generate compile-time build option list
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
serial_write('V');
|
||||
#endif
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
serial_write('N');
|
||||
#endif
|
||||
#ifdef ENABLE_M7
|
||||
serial_write('M');
|
||||
#endif
|
||||
#ifdef COREXY
|
||||
serial_write('C');
|
||||
#endif
|
||||
#ifdef PARKING_ENABLE
|
||||
serial_write('P');
|
||||
#endif
|
||||
#ifdef HOMING_FORCE_SET_ORIGIN
|
||||
serial_write('Z');
|
||||
#endif
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
serial_write('H');
|
||||
#endif
|
||||
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
|
||||
serial_write('L');
|
||||
#endif
|
||||
#ifdef USE_CLASSIC_REALTIME_REPORT
|
||||
serial_write('R');
|
||||
#endif
|
||||
#ifndef ENABLE_RESTORE_EEPROM_WIPE_ALL // NOTE: Shown when disabled.
|
||||
serial_write('*');
|
||||
#endif
|
||||
#ifndef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // NOTE: Shown when disabled.
|
||||
serial_write('$');
|
||||
#endif
|
||||
#ifndef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // NOTE: Shown when disabled.
|
||||
serial_write('#');
|
||||
#endif
|
||||
#ifndef ENABLE_BUILD_INFO_WRITE_COMMAND // NOTE: Shown when disabled.
|
||||
serial_write('I');
|
||||
#endif
|
||||
#ifndef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // NOTE: Shown when disabled.
|
||||
serial_write('E');
|
||||
#endif
|
||||
#ifndef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // NOTE: Shown when disabled.
|
||||
serial_write('W');
|
||||
#endif
|
||||
|
||||
// NOTE: Compiled values, like override increments/max/min values, may be added at some point later.
|
||||
// These will likely have a comma delimiter to separate them.
|
||||
|
||||
report_util_feedback_line_feed();
|
||||
}
|
||||
|
||||
|
||||
@ -663,15 +714,29 @@ void report_realtime_status()
|
||||
print_uint8_base10(sys.r_override);
|
||||
serial_write(',');
|
||||
print_uint8_base10(sys.spindle_speed_ovr);
|
||||
if (sys.toggle_ovr_mask) {
|
||||
printPgmString(PSTR("|T:"));
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK) { serial_write('S'); }
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_FLOOD_COOLANT) { serial_write('F'); }
|
||||
|
||||
uint8_t sp_state = spindle_get_state();
|
||||
uint8_t cl_state = coolant_get_state();
|
||||
if (sp_state || cl_state) {
|
||||
printPgmString(PSTR(",A:"));
|
||||
if (sp_state) { // != SPINDLE_STATE_DISABLE
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||
serial_write('S'); // CW
|
||||
#else
|
||||
if (sp_state == SPINDLE_STATE_CW) { serial_write('S'); } // CW
|
||||
else { serial_write('C'); } // CCW
|
||||
#endif
|
||||
#else
|
||||
if (sp_state & SPINDLE_STATE_CW) { serial_write('S'); } // CW
|
||||
else { serial_write('C'); } // CCW
|
||||
#endif
|
||||
}
|
||||
if (cl_state & COOLANT_STATE_FLOOD) { serial_write('F'); }
|
||||
#ifdef ENABLE_M7
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_MIST_COOLANT) { serial_write('M'); }
|
||||
if (cl_state & COOLANT_STATE_MIST) { serial_write('M'); }
|
||||
#endif
|
||||
bit_false(sys.toggle_ovr_mask, (TOGGLE_OVR_FLOOD_COOLANT|TOGGLE_OVR_FLOOD_COOLANT));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
printPgmString(PSTR(">\r\n"));
|
||||
@ -764,10 +829,17 @@ void report_realtime_status()
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Report realtime rate
|
||||
#ifdef REPORT_FIELD_CURRENT_RATE
|
||||
printPgmString(PSTR("|F:"));
|
||||
printFloat_RateValue(st_get_realtime_rate());
|
||||
// Report realtime feed speed
|
||||
#ifdef REPORT_FIELD_CURRENT_FEED_SPEED
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
printPgmString(PSTR("|FS:"));
|
||||
printFloat_RateValue(st_get_realtime_rate());
|
||||
serial_write(',');
|
||||
printFloat(sys.spindle_speed,N_DECIMAL_RPMVALUE);
|
||||
#else
|
||||
printPgmString(PSTR("|F:"));
|
||||
printFloat_RateValue(st_get_realtime_rate());
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef REPORT_FIELD_PIN_STATE
|
||||
@ -818,15 +890,28 @@ void report_realtime_status()
|
||||
serial_write(',');
|
||||
print_uint8_base10(sys.spindle_speed_ovr);
|
||||
|
||||
if (sys.toggle_ovr_mask) {
|
||||
printPgmString(PSTR("|T:"));
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK) { serial_write('S'); }
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_FLOOD_COOLANT) { serial_write('F'); }
|
||||
uint8_t sp_state = spindle_get_state();
|
||||
uint8_t cl_state = coolant_get_state();
|
||||
if (sp_state || cl_state) {
|
||||
printPgmString(PSTR("|A:"));
|
||||
if (sp_state) { // != SPINDLE_STATE_DISABLE
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||
serial_write('S'); // CW
|
||||
#else
|
||||
if (sp_state == SPINDLE_STATE_CW) { serial_write('S'); } // CW
|
||||
else { serial_write('C'); } // CCW
|
||||
#endif
|
||||
#else
|
||||
if (sp_state & SPINDLE_STATE_CW) { serial_write('S'); } // CW
|
||||
else { serial_write('C'); } // CCW
|
||||
#endif
|
||||
}
|
||||
if (cl_state & COOLANT_STATE_FLOOD) { serial_write('F'); }
|
||||
#ifdef ENABLE_M7
|
||||
if (sys.toggle_ovr_mask & TOGGLE_OVR_MIST_COOLANT) { serial_write('M'); }
|
||||
#endif
|
||||
bit_false(sys.toggle_ovr_mask, (TOGGLE_OVR_FLOOD_COOLANT|TOGGLE_OVR_FLOOD_COOLANT));
|
||||
}
|
||||
if (cl_state & COOLANT_STATE_MIST) { serial_write('M'); }
|
||||
#endif
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -28,9 +28,9 @@
|
||||
#endif
|
||||
#ifndef TX_BUFFER_SIZE
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
#define TX_BUFFER_SIZE 100
|
||||
#define TX_BUFFER_SIZE 112
|
||||
#else
|
||||
#define TX_BUFFER_SIZE 90
|
||||
#define TX_BUFFER_SIZE 104
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
@ -63,11 +63,41 @@ void spindle_init()
|
||||
}
|
||||
|
||||
|
||||
// Stop and start spindle routines. Called by all spindle routines and various interrupts.
|
||||
// Keep routine small, fast, and efficient.
|
||||
uint8_t spindle_get_state()
|
||||
{
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||
// No spindle direction output pin.
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
if (bit_isfalse(SPINDLE_ENABLE_PORT,(1<<SPINDLE_ENABLE_BIT))) { return(SPINDLE_STATE_CW); }
|
||||
#else
|
||||
if (bit_istrue(SPINDLE_ENABLE_PORT,(1<<SPINDLE_ENABLE_BIT))) { return(SPINDLE_STATE_CW); }
|
||||
#endif
|
||||
#else
|
||||
if (SPINDLE_TCCRA_REGISTER & (1<<SPINDLE_COMB_BIT)) { // Check if PWM is enabled.
|
||||
if (SPINDLE_DIRECTION_PORT & (1<<SPINDLE_DIRECTION_BIT)) { return(SPINDLE_STATE_CCW); }
|
||||
else { return(SPINDLE_STATE_CW); }
|
||||
}
|
||||
#endif
|
||||
#else
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
if (bit_isfalse(SPINDLE_ENABLE_PORT,(1<<SPINDLE_ENABLE_BIT))) {
|
||||
#else
|
||||
if (bit_istrue(SPINDLE_ENABLE_PORT,(1<<SPINDLE_ENABLE_BIT))) {
|
||||
#endif
|
||||
if (SPINDLE_DIRECTION_PORT & (1<<SPINDLE_DIRECTION_BIT)) { return(SPINDLE_STATE_CCW); }
|
||||
else { return(SPINDLE_STATE_CW); }
|
||||
}
|
||||
#endif
|
||||
return(SPINDLE_STATE_DISABLE);
|
||||
}
|
||||
|
||||
|
||||
// Disables the spindle and sets PWM output to zero when PWM variable spindle speed is enabled.
|
||||
// Called by various main program and ISR routines. Keep routine small, fast, and efficient.
|
||||
// Called by spindle_init(), spindle_set_speed(), spindle_set_state(), and mc_reset().
|
||||
void spindle_stop()
|
||||
{
|
||||
// On the Uno, spindle enable and PWM are shared. Other CPUs have seperate enable pin.
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
SPINDLE_TCCRA_REGISTER &= ~(1<<SPINDLE_COMB_BIT); // Disable PWM. Output voltage is zero.
|
||||
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||
@ -88,7 +118,8 @@ void spindle_stop()
|
||||
|
||||
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
// Called by spindle state functions and stepper ISR. Keep routine small, fast, and efficient.
|
||||
// Sets spindle speed PWM output and enable pin, if configured. Called by spindle_set_state()
|
||||
// and stepper ISR. Keep routine small and efficient.
|
||||
void spindle_set_speed(uint8_t pwm_value)
|
||||
{
|
||||
if (pwm_value == SPINDLE_PWM_OFF_VALUE) {
|
||||
@ -108,17 +139,25 @@ void spindle_stop()
|
||||
}
|
||||
|
||||
|
||||
// Called by spindle state functions and step segment generator.
|
||||
// Called by spindle_set_state() and step segment generator. Keep routine small and efficient.
|
||||
uint8_t spindle_compute_pwm_value(float rpm) // 328p PWM register is 8-bit.
|
||||
{
|
||||
rpm *= (0.01*sys.spindle_speed_ovr); // Scale by spindle speed override value.
|
||||
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
||||
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
|
||||
// No PWM range possible. Set simple on/off spindle control pin state.
|
||||
sys.spindle_speed = settings.rpm_max;
|
||||
return(SPINDLE_PWM_MAX_VALUE);
|
||||
} else if (rpm < settings.rpm_min) {
|
||||
if (rpm == 0.0) { return(SPINDLE_PWM_OFF_VALUE); }
|
||||
else { return(SPINDLE_PWM_MIN_VALUE); }
|
||||
if (rpm == 0.0) {
|
||||
sys.spindle_speed = 0.0;
|
||||
return(SPINDLE_PWM_OFF_VALUE); }
|
||||
else {
|
||||
sys.spindle_speed = settings.rpm_min;
|
||||
return(SPINDLE_PWM_MIN_VALUE);
|
||||
}
|
||||
} else {
|
||||
sys.spindle_speed = rpm;
|
||||
return(floor( (rpm-settings.rpm_min)*pwm_gradient + (SPINDLE_PWM_MIN_VALUE+0.5)));
|
||||
}
|
||||
}
|
||||
@ -126,18 +165,24 @@ void spindle_stop()
|
||||
|
||||
|
||||
// Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled.
|
||||
// Called by spindle_run() after sync and parking motion/spindle stop override during restore.
|
||||
void spindle_set_state(uint8_t state, uint8_t pwm_value)
|
||||
// Called by g-code parser spindle_sync(), parking retract and restore, g-code program end,
|
||||
// sleep, and spindle stop override.
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
void spindle_set_state(uint8_t state, float rpm)
|
||||
#else
|
||||
void spindle_set_state(uint8_t state)
|
||||
#endif
|
||||
{
|
||||
if (sys.abort) { return; } // Block during abort.
|
||||
|
||||
// Halt or set spindle direction and rpm.
|
||||
if (state == SPINDLE_DISABLE) {
|
||||
|
||||
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
sys.spindle_speed = 0.0;
|
||||
#endif
|
||||
spindle_stop();
|
||||
|
||||
|
||||
} else {
|
||||
|
||||
|
||||
#ifndef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||
if (state == SPINDLE_ENABLE_CW) {
|
||||
SPINDLE_DIRECTION_PORT &= ~(1<<SPINDLE_DIRECTION_BIT);
|
||||
@ -145,35 +190,39 @@ void spindle_set_state(uint8_t state, uint8_t pwm_value)
|
||||
SPINDLE_DIRECTION_PORT |= (1<<SPINDLE_DIRECTION_BIT);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
|
||||
spindle_set_speed(pwm_value);
|
||||
|
||||
spindle_set_speed(spindle_compute_pwm_value(rpm));
|
||||
#else
|
||||
|
||||
// NOTE: Without variable spindle, the enable bit should just turn on or off, regardless
|
||||
// if the spindle speed value is zero, as its ignored anyhow.
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
SPINDLE_ENABLE_PORT &= ~(1<<SPINDLE_ENABLE_BIT);
|
||||
#else
|
||||
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
}
|
||||
|
||||
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to report change immediately
|
||||
}
|
||||
|
||||
|
||||
// Called by g-code parser when setting spindle state and requires a buffer sync.
|
||||
void spindle_run(uint8_t state, float rpm)
|
||||
{
|
||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
spindle_set_state(state, spindle_compute_pwm_value(rpm));
|
||||
#else
|
||||
spindle_set_state(state,0); // Send null pwm value. Not used.
|
||||
#endif
|
||||
}
|
||||
// G-code parser entry-point for setting spindle state. Forces a planner buffer sync and bails
|
||||
// if an abort or check-mode is active.
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
void spindle_sync(uint8_t state, float rpm)
|
||||
{
|
||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
spindle_set_state(state,rpm);
|
||||
}
|
||||
#else
|
||||
void spindle_sync(uint8_t state)
|
||||
{
|
||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
spindle_set_state(state);
|
||||
}
|
||||
#endif
|
@ -22,22 +22,50 @@
|
||||
#ifndef spindle_control_h
|
||||
#define spindle_control_h
|
||||
|
||||
#define SPINDLE_NO_SYNC false
|
||||
#define SPINDLE_FORCE_SYNC true
|
||||
|
||||
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
|
||||
#define SPINDLE_STATE_CW bit(0)
|
||||
#define SPINDLE_STATE_CCW bit(1)
|
||||
|
||||
|
||||
// Initializes spindle pins and hardware PWM, if enabled.
|
||||
void spindle_init();
|
||||
|
||||
// Called by g-code parser when setting spindle state and requires a buffer sync.
|
||||
void spindle_run(uint8_t direction, float rpm);
|
||||
// Returns current spindle output state. Overrides may alter it from programmed states.
|
||||
uint8_t spindle_get_state();
|
||||
|
||||
// Called by g-code parser when setting spindle state and requires a buffer sync.
|
||||
// Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled.
|
||||
// Called by spindle_run() after sync and parking motion/spindle stop override during restore.
|
||||
void spindle_set_state(uint8_t state, uint8_t pwm_value);
|
||||
// Called by spindle_sync() after sync and parking motion/spindle stop override during restore.
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
|
||||
// Called by g-code parser when setting spindle state and requires a buffer sync.
|
||||
void spindle_sync(uint8_t state, float rpm);
|
||||
|
||||
// Sets spindle running state with direction, enable, and spindle PWM.
|
||||
void spindle_set_state(uint8_t state, float rpm);
|
||||
|
||||
// Sets spindle PWM quickly for stepper ISR. Also called by spindle_set_state().
|
||||
// NOTE: 328p PWM register is 8-bit.
|
||||
void spindle_set_speed(uint8_t pwm_value);
|
||||
|
||||
// Computes 328p-specific PWM register value for the given RPM for quick updating.
|
||||
uint8_t spindle_compute_pwm_value(float rpm);
|
||||
|
||||
#else
|
||||
|
||||
// Called by g-code parser when setting spindle state and requires a buffer sync.
|
||||
void spindle_sync(uint8_t state);
|
||||
|
||||
// Sets spindle running state with direction and enable.
|
||||
void spindle_set_state(uint8_t state);
|
||||
|
||||
#endif
|
||||
|
||||
// Stop and start spindle routines. Called by all spindle routines and stepper ISR.
|
||||
void spindle_stop();
|
||||
void spindle_set_speed(uint8_t pwm_value); // Variable spindle only.
|
||||
|
||||
uint8_t spindle_compute_pwm_value(float rpm); // 328p PWM register is 8-bit. Variable spindle only.
|
||||
|
||||
|
||||
#endif
|
||||
|
@ -746,8 +746,11 @@ void st_prep_buffer()
|
||||
if (sys.step_control & STEP_CONTROL_UPDATE_SPINDLE_PWM) {
|
||||
// Configure correct spindle PWM state for block. Updates with planner changes and spindle speed overrides.
|
||||
if (pl_block->condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)) {
|
||||
st_prep_block->spindle_pwm = spindle_compute_pwm_value((0.01*sys.spindle_speed_ovr)*pl_block->spindle_speed);
|
||||
} else { st_prep_block->spindle_pwm = SPINDLE_PWM_OFF_VALUE; }
|
||||
st_prep_block->spindle_pwm = spindle_compute_pwm_value(pl_block->spindle_speed);
|
||||
} else {
|
||||
sys.spindle_speed = 0.0;
|
||||
st_prep_block->spindle_pwm = SPINDLE_PWM_OFF_VALUE;
|
||||
}
|
||||
bit_false(sys.step_control,STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
}
|
||||
#endif
|
||||
|
@ -174,17 +174,26 @@ uint8_t system_execute_line(char *line)
|
||||
else { report_ngc_parameters(); }
|
||||
break;
|
||||
case 'H' : // Perform homing cycle [IDLE/ALARM]
|
||||
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
|
||||
// Block if safety door is ajar.
|
||||
if (system_check_safety_door_ajar()) { return(STATUS_CHECK_DOOR); }
|
||||
sys.state = STATE_HOMING; // Set system state variable
|
||||
mc_homing_cycle();
|
||||
if (!sys.abort) { // Execute startup scripts after successful homing.
|
||||
sys.state = STATE_IDLE; // Set to IDLE when complete.
|
||||
st_go_idle(); // Set steppers to the settings idle state before returning.
|
||||
system_execute_startup(line);
|
||||
}
|
||||
} else { return(STATUS_SETTING_DISABLED); }
|
||||
if (bit_isfalse(settings.flags,BITFLAG_HOMING_ENABLE)) {return(STATUS_SETTING_DISABLED); }
|
||||
if (system_check_safety_door_ajar()) { return(STATUS_CHECK_DOOR); } // Block if safety door is ajar.
|
||||
sys.state = STATE_HOMING; // Set system state variable
|
||||
if (line[2] == 0) {
|
||||
mc_homing_cycle(HOMING_CYCLE_ALL);
|
||||
#ifdef HOMING_SINGLE_AXIS_COMMANDS
|
||||
} else if (line[3] == 0) {
|
||||
switch (line[2]) {
|
||||
case 'X': mc_homing_cycle(HOMING_CYCLE_X); break;
|
||||
case 'Y': mc_homing_cycle(HOMING_CYCLE_Y); break;
|
||||
case 'Z': mc_homing_cycle(HOMING_CYCLE_Z); break;
|
||||
default: return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
#endif
|
||||
} else { return(STATUS_INVALID_STATEMENT); }
|
||||
if (!sys.abort) { // Execute startup scripts after successful homing.
|
||||
sys.state = STATE_IDLE; // Set to IDLE when complete.
|
||||
st_go_idle(); // Set steppers to the settings idle state before returning.
|
||||
if (line[2] == 0) { system_execute_startup(line); }
|
||||
}
|
||||
break;
|
||||
case 'S' : // Puts Grbl to sleep [IDLE/ALARM]
|
||||
if ((line[2] != 'L') || (line[3] != 'P') || (line[4] != 0)) { return(STATUS_INVALID_STATEMENT); }
|
||||
|
@ -114,15 +114,12 @@
|
||||
#define CONTROL_PIN_INDEX_CYCLE_START bit(2)
|
||||
#endif
|
||||
|
||||
// Define toggle override control states.
|
||||
#define TOGGLE_OVR_STOP_ENABLED bit(0)
|
||||
#define TOGGLE_OVR_STOP_INITIATE bit(1)
|
||||
#define TOGGLE_OVR_STOP_RESTORE bit(2)
|
||||
#define TOGGLE_OVR_STOP_RESTORE_CYCLE bit(3)
|
||||
#define TOGGLE_OVR_FLOOD_COOLANT bit(4)
|
||||
#define TOGGLE_OVR_MIST_COOLANT bit(5)
|
||||
#define TOGGLE_OVR_STOP_ACTIVE_MASK (TOGGLE_OVR_STOP_ENABLED|TOGGLE_OVR_STOP_INITIATE|TOGGLE_OVR_STOP_RESTORE|TOGGLE_OVR_STOP_RESTORE_CYCLE)
|
||||
// NOTE: Mask is used to determine if spindle stop is active or disabled.
|
||||
// Define spindle stop override control states.
|
||||
#define SPINDLE_STOP_OVR_DISABLED 0 // Must be zero.
|
||||
#define SPINDLE_STOP_OVR_ENABLED bit(0)
|
||||
#define SPINDLE_STOP_OVR_INITIATE bit(1)
|
||||
#define SPINDLE_STOP_OVR_RESTORE bit(2)
|
||||
#define SPINDLE_STOP_OVR_RESTORE_CYCLE bit(3)
|
||||
|
||||
|
||||
// Define global system variables
|
||||
@ -137,9 +134,12 @@ typedef struct {
|
||||
uint8_t f_override; // Feed rate override value in percent
|
||||
uint8_t r_override; // Rapids override value in percent
|
||||
uint8_t spindle_speed_ovr; // Spindle speed value in percent
|
||||
uint8_t toggle_ovr_mask; // Tracks toggle override states
|
||||
uint8_t spindle_stop_ovr; // Tracks spindle stop override states
|
||||
uint8_t report_ovr_counter; // Tracks when to add override data to status reports.
|
||||
uint8_t report_wco_counter; // Tracks when to add work coordinate offset data to status reports.
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
float spindle_speed;
|
||||
#endif
|
||||
} system_t;
|
||||
extern system_t sys;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user