Merge branch 'edge'

This commit is contained in:
Sungeun Jeon 2015-03-15 22:01:10 -06:00
commit 46c943f13d
66 changed files with 2083 additions and 17108 deletions

2
.gitignore vendored
View File

@ -3,3 +3,5 @@
*.elf *.elf
*.DS_Store *.DS_Store
*.d *.d
README.md

45
COPYING
View File

@ -1,56 +1,31 @@
------------------------------------------------------------------------------ ------------------------------------------------------------------------------
COPYRIGHT NOTICE FOR GRBL v0.9: COPYRIGHT NOTICE FOR GRBL:
------------------------------------------------------------------------------ ------------------------------------------------------------------------------
GRBL v0.9 - Embedded CNC g-code interpreter and motion-controller Grbl - Embedded CNC g-code interpreter and motion-controller
Copyright (c) 2012-2014 Sungeun K. Jeon
This program is free software: you can redistribute it and/or modify Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011 Jens Geisler
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
This program is distributed in the hope that it will be useful, Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
------------------------------------------------------------------------------ ------------------------------------------------------------------------------
COPYRIGHT NOTICE(S) FOR WORK CONTAINED IN THIS SOFTWARE: COPYRIGHT NOTICE(S) FOR WORK CONTAINED IN THIS SOFTWARE:
------------------------------------------------------------------------------ ------------------------------------------------------------------------------
The MIT License (MIT)
GRBL(tm) v0.8 - Embedded CNC g-code interpreter and motion-controller
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2013 Sungeun K. Jeon
Copyright (c) 2011 Jens Geisler
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
-------------
Copyright (c) 2008, Atmel Corporation All rights reserved. Copyright (c) 2008, Atmel Corporation All rights reserved.
Redistribution and use in source and binary forms, with or without Redistribution and use in source and binary forms, with or without
@ -704,5 +679,3 @@ Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee. copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS END OF TERMS AND CONDITIONS
------------------------------------------------------------------------------

View File

@ -1,7 +1,7 @@
# Part of Grbl # Part of Grbl
# #
# Copyright (c) 2009-2011 Simen Svale Skogsrud # Copyright (c) 2009-2011 Simen Svale Skogsrud
# Copyright (c) 2012 Sungeun K. Jeon # Copyright (c) 2012-2015 Sungeun K. Jeon
# #
# Grbl is free software: you can redistribute it and/or modify # Grbl is free software: you can redistribute it and/or modify
# it under the terms of the GNU General Public License as published by # it under the terms of the GNU General Public License as published by
@ -31,9 +31,11 @@
DEVICE ?= atmega328p DEVICE ?= atmega328p
CLOCK = 16000000 CLOCK = 16000000
PROGRAMMER ?= -c avrisp2 -P usb PROGRAMMER ?= -c avrisp2 -P usb
OBJECTS = main.o motion_control.o gcode.o spindle_control.o coolant_control.o serial.o \ SOURCE = main.c motion_control.c gcode.c spindle_control.c coolant_control.c serial.c \
protocol.o stepper.o eeprom.o settings.o planner.o nuts_bolts.o limits.o \ protocol.c stepper.c eeprom.c settings.c planner.c nuts_bolts.c limits.c \
print.o probe.o report.o system.o print.c probe.c report.c system.c
BUILDDIR = build
SOURCEDIR = grbl
# FUSES = -U hfuse:w:0xd9:m -U lfuse:w:0x24:m # FUSES = -U hfuse:w:0xd9:m -U lfuse:w:0x24:m
FUSES = -U hfuse:w:0xd2:m -U lfuse:w:0xff:m FUSES = -U hfuse:w:0xd2:m -U lfuse:w:0xff:m
@ -42,22 +44,23 @@ FUSES = -U hfuse:w:0xd2:m -U lfuse:w:0xff:m
AVRDUDE = avrdude $(PROGRAMMER) -p $(DEVICE) -B 10 -F AVRDUDE = avrdude $(PROGRAMMER) -p $(DEVICE) -B 10 -F
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
OBJECTS = $(addprefix $(BUILDDIR)/,$(notdir $(SOURCE:.c=.o)))
# symbolic targets: # symbolic targets:
all: grbl.hex all: grbl.hex
.c.o: $(BUILDDIR)/%.o: $(SOURCEDIR)/%.c
$(COMPILE) -c $< -o $@ $(COMPILE) -MMD -MP -c $< -o $@
@$(COMPILE) -MM $< > $*.d
.S.o: .S.o:
$(COMPILE) -x assembler-with-cpp -c $< -o $@ $(COMPILE) -x assembler-with-cpp -c $< -o $(BUILDDIR)/$@
# "-x assembler-with-cpp" should not be necessary since this is the default # "-x assembler-with-cpp" should not be necessary since this is the default
# file type for the .S (with capital S) extension. However, upper case # file type for the .S (with capital S) extension. However, upper case
# characters are not always preserved on Windows. To ensure WinAVR # characters are not always preserved on Windows. To ensure WinAVR
# compatibility define the file type manually. # compatibility define the file type manually.
.c.s: #.c.s:
$(COMPILE) -S $< -o $@ $(COMPILE) -S $< -o $(BUILDDIR)/$@
flash: all flash: all
$(AVRDUDE) -U flash:w:grbl.hex:i $(AVRDUDE) -U flash:w:grbl.hex:i
@ -73,25 +76,25 @@ load: all
bootloadHID grbl.hex bootloadHID grbl.hex
clean: clean:
rm -f grbl.hex main.elf $(OBJECTS) $(OBJECTS:.o=.d) rm -f grbl.hex $(BUILDDIR)/*.o $(BUILDDIR)/*.d $(BUILDDIR)/*.elf
# file targets: # file targets:
main.elf: $(OBJECTS) $(BUILDDIR)/main.elf: $(OBJECTS)
$(COMPILE) -o main.elf $(OBJECTS) -lm -Wl,--gc-sections $(COMPILE) -o $(BUILDDIR)/main.elf $(OBJECTS) -lm -Wl,--gc-sections
grbl.hex: main.elf grbl.hex: $(BUILDDIR)/main.elf
rm -f grbl.hex rm -f grbl.hex
avr-objcopy -j .text -j .data -O ihex main.elf grbl.hex avr-objcopy -j .text -j .data -O ihex $(BUILDDIR)/main.elf grbl.hex
avr-size --format=berkeley main.elf avr-size --format=berkeley $(BUILDDIR)/main.elf
# If you have an EEPROM section, you must also create a hex file for the # If you have an EEPROM section, you must also create a hex file for the
# EEPROM and add it to the "flash" target. # EEPROM and add it to the "flash" target.
# Targets for code debugging and analysis: # Targets for code debugging and analysis:
disasm: main.elf disasm: main.elf
avr-objdump -d main.elf avr-objdump -d $(BUILDDIR)/main.elf
cpp: cpp:
$(COMPILE) -E main.c $(COMPILE) -E $(SOURCEDIR)/main.c
# include generated header dependencies # include generated header dependencies
-include $(OBJECTS:.o=.d) -include $(BUILDDIR)/$(OBJECTS:.o=.d)

View File

@ -1,83 +0,0 @@
#Grbl - An embedded g-code interpreter and motion-controller for the Arduino/AVR328 microcontroller
***
Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. It will run on a vanilla Arduino (Duemillanove/Uno) as long as it sports an Atmega 328.
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.
It accepts standards-compliant g-code and has been tested with the output of several CAM tools with no problems. Arcs, circles and helical motion are fully supported, as well as, all other primary g-code commands. Macro functions, variables, and most canned cycles are not supported, but we think GUIs can do a much better job at translating them into straight g-code anyhow.
Grbl includes full acceleration management with look ahead. That means the controller will look up to 18 motions into the future and plan its velocities ahead to deliver smooth acceleration and jerk-free cornering.
* [Licensing](https://github.com/grbl/grbl/wiki/Licensing): Grbl v0.9 is free software, released under the GPLv3 license. Obsolete versions of Grbl, v0.8 and prior, are released under the permissive MIT-license. This will ensure Grbl will always be an open-source project while making the code permissive for others.
* For more information and help, check out our **[Wiki pages!](https://github.com/grbl/grbl/wiki)** If you find that the information is out-dated, please to help us keep it updated by editing it or notifying our community! Thanks!
* Lead Developer [_2011 - Current_]: Sonny Jeon, Ph.D. (USA)
* Lead Developer [_2009 - 2011_]: Simen Svale Skogsrud (Norway). aka The Originator/Creator/Pioneer/Father of Grbl.
***
_**Master Branch:**_
* [Grbl v0.9g Atmega328p 16mhz 115200baud with generic defaults](http://bit.ly/1m8E1Qa) _(2014-09-05)_
* [Grbl v0.9g Atmega328p 16mhz 115200baud with ShapeOko2 defaults](http://bit.ly/1kOAzig) _(2014-09-05)_
- **IMPORTANT INFO WHEN UPGRADING TO GRBL v0.9g:**
- Baudrate is now **115200** (Up from 9600).
- Settings WILL be overwritten. Please make sure you have a backup. Also, settings have been renumbered and some have changed how they work. See our [Configuring v0.9 Wiki page](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9) for details.
_**Archives:**_
* [Grbl v0.8c Atmega328p 16mhz 9600baud](http://bit.ly/SSdCJE)
* [Grbl v0.7d Atmega328p 16mhz 9600baud](http://bit.ly/ZhL15G)
* [Grbl v0.6b Atmega328p 16mhz 9600baud](http://bit.ly/VD04A5)
* [Grbl v0.51 Atmega328p 16mhz 9600baud](http://bit.ly/W75BS1)
* [Grbl v0.6b Atmega168 16mhz 9600baud](http://bit.ly/SScWnE)
* [Grbl v0.51 Atmega168 16mhz 9600baud](http://bit.ly/VXyrYu)
-------------
_Grbl is an open-source project and fueled by the free-time of our intrepid administrators and altruistic users. If you'd like to donate, all proceeds will be used to help keep this project sustainable and to fund supporting equipment. Thank you!_
| [![Donate](https://www.paypalobjects.com/en_US/i/btn/btn_donate_LG.gif)](https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=EBQWAWQAAT878) | [![Flattr Grbl](http://api.flattr.com/button/flattr-badge-large.png)](https://flattr.com/submit/auto?user_id=chamnit&url=github.com/grbl/grbl&title=Grbl&language=&tags=github&category=software) | [![Support via Gratipay](https://cdn.rawgit.com/gratipay/gratipay-badge/2.1.3/dist/gratipay.png)](https://gratipay.com/chamnit/) |
|:--:|:--:|:--:|
***
##Update Summary for v0.9 from v0.8
- **IMPORTANT: Default serial baudrate is now 115200! (Up from 9600). And your settings will be over-written! Make sure to have a backup.**
- **_NEW_ Super Smooth Stepper Algorithm:** Complete overhaul of the handling of the stepper driver to simplify and reduce task time per ISR tick. Much smoother operation with the new Adaptive Multi-Axis Step Smoothing (AMASS) algorithm which does what its name implies (see stepper.c source for details). Users should immediately see significant improvements in how their machines move and overall performance!
- **Stability and Robustness Updates:** Grbl's overall stability has been focused on for this version. The planner and step-execution interface has been completely re-written for robustness and incorruptibility by the introduction of an intermediate step segment buffer that "checks-out" steps from the planner buffer in real-time. This means we can now fearlessly drive Grbl to it's highest limits. Combined with the new stepper algorithm and planner optimizations, this translated to **5x to 10x** overall performance increases in our testing! Also, stability and robustness tests have been reported to easily take 1.4 million (yes, **million**) line g-code programs like a champ!
- **(x4)+ Faster Planner:** Planning computations improved four-fold or more by optimizing end-to-end operations, which included streamlining the computations and introducing a planner pointer to locate un-improvable portions of the buffer and not waste cycles recomputing them.
- **Compile-able via Arduino IDE!:** Grbl's source code may be now download and altered, and then be compiled and flashed directly through the Arduino IDE, which should work on all platforms. See the Wiki for details on how to do it.
- **G-Code Parser Overhaul:** Completely re-written from the ground-up for 100%-compliance* to the g-code standard. (* Parts of the NIST standard are a bit out-dated and arbitrary, so we altered some minor things to make more sense. Differences are outlined in the source code.) We also took steps to allow us to break up the g-code parser into distinct separate tasks, which is key for some future development ideas and improvements.
- **Independent Acceleration and Velocity Settings:** Each axes may be defined with unique acceleration and velocity parameters and Grbl will automagically calculate the maximum acceleration and velocity through a path depending on the direction traveled. This is very useful for machines that have very different axes properties, like the ShapeOko's z-axis.
- **Soft Limits:** Checks if any motion command exceeds workspace limits before executing it, and alarms out, if detected. Another safety feature, but, unlike hard limits, position does not get lost, as it forces a feed hold before erroring out. NOTE: This still requires limit switches for homing so Grbl knows where the machine origin is, and the new max axis travel settings configured correctly for the machine.
- **Probing:** The G38.2 straight probe and G43.1/49 tool offset g-code commands are now supported. A simple probe switch must be connected to the Uno analog pin 5 (normally-open to ground). Grbl will report the probe position back to the user when the probing cycle detects a pin state change.
- **Tool Length Offsets:** Probing doesn't make sense without tool length offsets(TLO), so we added it! The G43.1 dynamic TLO (described by linuxcnc.org) and G49 TLO cancel commands are now supported. G43.1 dynamic TLO works like the normal G43 TLO(NOT SUPPORTED) but requires an additional axis word with the offset value attached. We did this so Grbl does not have to track and maintain a tool offset database in its memory. Perhaps in the future, we will support a tool database, but not for this version.
- **Improved Arc Performance:** The larger the arc radius, the faster Grbl will trace it! We are now defining arcs in terms of arc chordal tolerance, rather than a fixed segment length. This automatically scales the arc segment length such that maximum radial error of the segment from the true arc is never more than the chordal tolerance value of a super-accurate default of 0.002 mm.
- **CPU Pin Mapping:** In an effort for Grbl to be compatible with other AVR architectures, such as the 1280 or 2560, a new cpu_map.h pin configuration file has been created to allow Grbl to be compiled for them. This is currently user supported, so your mileage may vary. If you run across a bug, please let us know or better send us a fix! Thanks in advance!
- **New Grbl SIMULATOR! (by @jgeisler and @ashelly):** A completely independent wrapper of the Grbl main source code that may be compiled as an executable on a computer. No Arduino required. Simply simulates the responses of Grbl as if it was on an Arduino. May be used for many things: checking out how Grbl works, pre-process moves for GUI graphics, debugging of new features, etc. Much left to do, but potentially very powerful, as the dummy AVR variables can be written to output anything you need.
- **Configurable Real-time Status Reporting:** Users can now customize the type of real-time data Grbl reports back when they issue a '?' status report. This includes data such as: machine position, work position, planner buffer usage, serial RX buffer usage.
- **Updated Homing Routine:** Sets workspace volume in all negative space regardless of limit switch position. Common on pro CNCs. But, the behavior may be changed by a compile-time option though. Now tied directly into the main planner and stepper modules to reduce flash space and allow maximum speeds during seeking.
- **Optional Limit Pin Sharing:** Limit switches can be combined to share the same pins to free up precious I/O pins for other purposes. When combined, users must adjust the homing cycle mask in config.h to not home the axes on a shared pin at the same time. Don't worry; hard limits and the homing cycle still work just like they did before.
- **Optional Variable Spindle Speed Output:** Available only as a compile-time option through the config.h file. Enables PWM output for 'S' g-code commands. Enabling this feature will swap the Z-limit D11 pin and spindle enable D12 pin to access the hardware PWM on pin D11. The Z-limit pin, now on D12, should work just as it did before.
- **Additional Compile-Time Feature Options:** Line number tracking, real-time feed rate reporting.
- **SLATED FOR v1.0 DEVELOPMENT** Jogging controls and feedrate/spindle/coolant overrides. (In v0.9, the framework for feedrate overrides are in-place, only the minor details to complete it have yet to be installed.)
-
```
List of Supported G-Codes in Grbl v0.9
- Non-Modal Commands: G4, G10 L2, G10 L20, G28, G30, G28.1, G30.1, G53, G92, G92.1
- Motion Modes: G0, G1, G2, G3, G38.1, G80
- Feed Rate Modes: G93, G94
- Unit Modes: G20, G21
- Distance Modes: G90, G91
- Plane Select Modes: G17, G18, G19
- Tool Length Offset Modes: G43.1, G49
- Coordinate System Modes: G54, G55, G56, G57, G58, G59
- Program Flow: M0, M1, M2, M30*
- Coolant Control: M7*, M8, M9
- Spindle Control: M3, M4, M5
```

4
build/.gitignore vendored Normal file
View File

@ -0,0 +1,4 @@
# Ignore everything in this directory
*
# Except this file
!.gitignore

Binary file not shown.

After

Width:  |  Height:  |  Size: 10 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 41 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 57 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

BIN
doc/logo/Grbl Logo.pdf Normal file

Binary file not shown.

134
doc/logo/Grbl Logo.svg Normal file
View File

@ -0,0 +1,134 @@
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
<svg
xmlns:dc="http://purl.org/dc/elements/1.1/"
xmlns:cc="http://creativecommons.org/ns#"
xmlns:rdf="http://www.w3.org/1999/02/22-rdf-syntax-ns#"
xmlns:svg="http://www.w3.org/2000/svg"
xmlns="http://www.w3.org/2000/svg"
xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd"
xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape"
width="744.094488189"
height="1052.36220472"
id="svg2"
version="1.1"
inkscape:version="0.91 r13725"
sodipodi:docname="Grbl Logo.svg">
<metadata
id="metadata97">
<rdf:RDF>
<cc:Work
rdf:about="">
<dc:format>image/svg+xml</dc:format>
<dc:type
rdf:resource="http://purl.org/dc/dcmitype/StillImage" />
<dc:title />
</cc:Work>
</rdf:RDF>
</metadata>
<sodipodi:namedview
pagecolor="#ffffff"
bordercolor="#666666"
borderopacity="1"
objecttolerance="10"
gridtolerance="10"
guidetolerance="10"
inkscape:pageopacity="0"
inkscape:pageshadow="2"
inkscape:window-width="1000"
inkscape:window-height="751"
id="namedview95"
showgrid="false"
inkscape:zoom="0.89702957"
inkscape:cx="393.978"
inkscape:cy="560.38231"
inkscape:window-x="0"
inkscape:window-y="0"
inkscape:window-maximized="0"
inkscape:current-layer="g21" />
<desc
id="desc4">/Users/chamnit/Dropbox/documents/OHS/Logo/Grbl.DXF - scale = 58.043118, origin = (0.000000, 0.000000), auto = True</desc>
<defs
id="defs6">
<marker
id="DistanceX"
orient="auto"
refX="0.0"
refY="0.0"
style="overflow:visible">
<path
d="M 3,-3 L -3,3 M 0,-5 L 0,5"
style="stroke:#000000; stroke-width:0.5"
id="path9" />
</marker>
<pattern
height="8"
id="Hatch"
patternUnits="userSpaceOnUse"
width="8"
x="0"
y="0">
<path
d="M8 4 l-4,4"
linecap="square"
stroke="#000000"
stroke-width="0.25"
id="path12" />
<path
d="M6 2 l-4,4"
linecap="square"
stroke="#000000"
stroke-width="0.25"
id="path14" />
<path
d="M4 0 l-4,4"
linecap="square"
stroke="#000000"
stroke-width="0.25"
id="path16" />
</pattern>
<symbol
id="*Model_Space" />
<symbol
id="*Paper_Space" />
<symbol
id="*Paper_Space0" />
</defs>
<g
inkscape:groupmode="layer"
inkscape:label="0"
id="g21">
<g
id="g3562"
transform="matrix(0.74854703,0,0,0.74854703,93.578346,130.5299)">
<path
sodipodi:nodetypes="ccscccccc"
inkscape:connector-curvature="0"
id="path45"
style="fill:#000000;stroke:#000000;stroke-linecap:round"
d="m 666.97027,519.20619 0,-204.22494 c 0,-14.19819 -11.5099,-25.70806 -25.70807,-25.70806 -14.19818,0 -25.70808,11.50987 -25.70808,25.70806 l 0,204.22494 c 0,56.79271 46.03958,102.83229 102.83229,102.8323 l 25.70808,-25.70808 -25.70808,-25.70807 c -28.39635,0 -51.41614,-23.0198 -51.41614,-51.41615 z" />
<path
sodipodi:nodetypes="ccsccccccc"
inkscape:connector-curvature="0"
id="path61"
style="fill:#000000;stroke:#000000;stroke-linecap:round"
d="m 230.65284,519.20619 0,77.12422 c 0,14.19819 11.5099,25.70806 25.70807,25.70806 14.19818,0 25.70808,-11.50987 25.70808,-25.70806 l 0,-77.12422 c 0,-28.39635 23.01979,-51.41615 51.41614,-51.41615 l 38.92203,0 0,-51.41614 -38.92203,0 c -56.7927,1e-5 -102.83228,46.03959 -102.83229,102.83229" />
<path
sodipodi:nodetypes="ccccssscccccsssc"
inkscape:connector-curvature="0"
id="path73"
style="fill:#000000;stroke:#000000;stroke-linecap:round"
d="m 487.73358,416.3739 -38.92203,0 0,51.41614 38.92203,0 c 20.79587,0 39.54419,12.52721 47.50197,31.73975 7.95777,19.21249 3.55772,41.32642 -11.14711,56.03126 -14.70484,14.70483 -36.81877,19.10488 -56.03126,11.14711 -19.21254,-7.95778 -31.73975,-26.7061 -31.73975,-47.50197 l 0,-204.22494 -25.70808,-25.70807 -25.70807,25.70807 0,204.22494 c 0,41.59174 25.05442,79.08838 63.47948,95.00395 38.42499,15.91554 82.65286,7.11546 112.06254,-22.29421 29.40967,-29.40968 38.20976,-73.63755 22.29423,-112.06254 -15.91557,-38.42506 -53.41221,-63.47949 -95.00395,-63.47949" />
<path
sodipodi:nodetypes="cssscccscccsssccccc"
inkscape:connector-curvature="0"
id="path81"
style="fill:#000000;stroke:#000000;stroke-linecap:round"
d="m 102.8323,570.62234 c -20.795869,0 -39.544189,-12.52721 -47.501976,-31.73974 -7.95777,-19.21249 -3.557731,-41.32643 11.147104,-56.03126 14.704835,-14.70484 36.818772,-19.10489 56.031262,-11.14712 19.21254,7.95778 31.73975,26.7061 31.73975,47.50197 l 0,127.10072 c 0,28.39635 -23.01979,51.41615 -51.41614,51.41615 -14.192584,0.008 -25.693722,11.51549 -25.693722,25.70807 0,14.19258 11.501138,25.70007 25.693722,25.70807 56.7927,-10e-6 102.83228,-46.03959 102.83229,-102.83229 l 0,-127.10072 c 0,-41.59174 -25.05443,-79.08838 -63.47949,-95.00395 C 103.76011,408.28671 59.532236,417.0868 30.122564,446.49647 0.712891,475.90615 -8.0871904,520.13402 7.8283485,558.55901 23.74392,596.98407 61.240561,622.03849 102.8323,622.03849 l 25.70807,0 25.70807,-25.70808 -25.70807,-25.70807 -25.70807,0" />
<path
inkscape:connector-curvature="0"
id="path91"
style="fill:none;stroke:#000000;stroke-linecap:round"
d="m 744.09449,596.33041 -25.70808,25.70808" />
</g>
</g>
</svg>

After

Width:  |  Height:  |  Size: 5.6 KiB

View File

@ -1,37 +0,0 @@
/*
eeprom.h - EEPROM methods
Part of Grbl
The MIT License (MIT)
GRBL(tm) - Embedded CNC g-code interpreter and motion-controller
Copyright (c) 2009-2011 Simen Svale Skogsrud
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
*/
#ifndef eeprom_h
#define eeprom_h
unsigned char eeprom_get_char(unsigned int addr);
void eeprom_put_char(unsigned int addr, unsigned char new_value);
void memcpy_to_eeprom_with_checksum(unsigned int destination, char *source, unsigned int size);
int memcpy_from_eeprom_with_checksum(char *destination, unsigned int source, unsigned int size);
#endif

View File

@ -1,8 +1,9 @@
/* /*
config.h - compile time configuration config.h - compile time configuration
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2013-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2013 Sungeun K. Jeon
*/
// This file contains compile-time configurations for Grbl's internal system. For the most part, // This file contains compile-time configurations for Grbl's internal system. For the most part,
// users will not need to directly modify these, but they are here for specific needs, i.e. // users will not need to directly modify these, but they are here for specific needs, i.e.
@ -32,7 +27,7 @@
#ifndef config_h #ifndef config_h
#define config_h #define config_h
#include "system.h" #include "grbl.h" // For Arduino IDE compatibility.
// Default settings. Used when resetting EEPROM. Change to desired name in defaults.h // Default settings. Used when resetting EEPROM. Change to desired name in defaults.h
@ -43,9 +38,9 @@
// Default cpu mappings. Grbl officially supports the Arduino Uno only. Other processor types // Default cpu mappings. Grbl officially supports the Arduino Uno only. Other processor types
// may exist from user-supplied templates or directly user-defined in cpu_map.h // may exist from user-supplied templates or directly user-defined in cpu_map.h
#define CPU_MAP_ATMEGA328P_TRADITIONAL // Arduino Uno CPU #define CPU_MAP_ATMEGA328P // Arduino Uno CPU
// Define runtime command special characters. These characters are 'picked-off' directly from the // Define realtime command special characters. These characters are 'picked-off' directly from the
// serial read data stream and are not passed to the grbl line execution parser. Select characters // serial read data stream and are not passed to the grbl line execution parser. Select characters
// that do not and must not exist in the streamed g-code program. ASCII control characters may be // that do not and must not exist in the streamed g-code program. ASCII control characters may be
// used, if they are available per user setup. Also, extended ASCII codes (>127), which are never in // used, if they are available per user setup. Also, extended ASCII codes (>127), which are never in
@ -55,6 +50,7 @@
#define CMD_FEED_HOLD '!' #define CMD_FEED_HOLD '!'
#define CMD_CYCLE_START '~' #define CMD_CYCLE_START '~'
#define CMD_RESET 0x18 // ctrl-x. #define CMD_RESET 0x18 // ctrl-x.
#define CMD_SAFETY_DOOR '@'
// If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces // If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces
// the user to perform the homing cycle (or override the locks) before doing anything else. This is // the user to perform the homing cycle (or override the locks) before doing anything else. This is
@ -107,6 +103,14 @@
#define N_DECIMAL_RATEVALUE_MM 0 // Rate or velocity value in mm/min #define N_DECIMAL_RATEVALUE_MM 0 // Rate or velocity value in mm/min
#define N_DECIMAL_SETTINGVALUE 3 // Decimals for floating point setting values #define N_DECIMAL_SETTINGVALUE 3 // Decimals for floating point setting values
// If your machine has two limits switches wired in parallel to one axis, you will need to enable
// this feature. Since the two switches are sharing a single pin, there is no way for Grbl to tell
// which one is enabled. This option only effects homing, where if a limit is engaged, Grbl will
// alarm out and force the user to manually disengage the limit switch. Otherwise, if you have one
// limit switch for each axis, don't enable this option. By keeping it disabled, you can perform a
// homing cycle while on the limit switch and not have to move the machine off of it.
// #define LIMITS_TWO_SWITCHES_ON_AXES
// Allows GRBL to track and report gcode line numbers. Enabling this means that the planning buffer // Allows GRBL to track and report gcode line numbers. Enabling this means that the planning buffer
// goes from 18 or 16 to make room for the additional line number data in the plan_block_t struct // goes from 18 or 16 to make room for the additional line number data in the plan_block_t struct
// #define USE_LINE_NUMBERS // Disabled by default. Uncomment to enable. // #define USE_LINE_NUMBERS // Disabled by default. Uncomment to enable.
@ -126,9 +130,62 @@
// NOTE: The M8 flood coolant control pin on analog pin 4 will still be functional regardless. // NOTE: The M8 flood coolant control pin on analog pin 4 will still be functional regardless.
// #define ENABLE_M7 // Disabled by default. Uncomment to enable. // #define ENABLE_M7 // Disabled by default. Uncomment to enable.
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
// immediately forces a feed hold and then safely de-energizes the machine. Resuming is blocked until
// the safety door is re-engaged. When it is, Grbl will re-energize the machine and then resume on the
// previous tool path, as if nothing happened.
// #define ENABLE_SAFETY_DOOR_INPUT_PIN // Default disabled. Uncomment to enable.
// After the safety door switch has been toggled and restored, this setting sets the power-up delay
// between restoring the spindle and coolant and resuming the cycle.
// NOTE: Delay value is defined in milliseconds from zero to 65,535.
#define SAFETY_DOOR_SPINDLE_DELAY 4000
#define SAFETY_DOOR_COOLANT_DELAY 1000
// Enable CoreXY kinematics. Use ONLY with CoreXY machines.
// IMPORTANT: If homing is enabled, you must reconfigure the homing cycle #defines above to
// #define HOMING_CYCLE_0 (1<<X_AXIS) and #define HOMING_CYCLE_1 (1<<Y_AXIS)
// NOTE: This configuration option alters the motion of the X and Y axes to principle of operation
// defined at (http://corexy.com/theory.html). Motors are assumed to positioned and wired exactly as
// described, if not, motions may move in strange directions. Grbl assumes the CoreXY A and B motors
// have the same steps per mm internally.
// #define COREXY // Default disabled. Uncomment to enable.
// Inverts pin logic of the control command pins. This essentially means when this option is enabled
// you can use normally-closed switches, rather than the default normally-open switches.
// NOTE: Will eventually be added to Grbl settings in v1.0.
// #define INVERT_CONTROL_PIN // Default disabled. Uncomment to enable.
// Enable limit pin states feedback in status reports. The data is presented as 0 (low) or 1(high),
// where the order is XYZ. For example, if the Y- and Z-limit pins are active, Grbl will include the
// following string in the status report "Lim:011". This is generally useful for setting up a new
// CNC machine, but we do not recommend keeping this option enabled, as it will consume CPU resources
// with little to no benefit during normal operation and it may not be supported by most GUIs.
// #define REPORT_LIMIT_PIN_STATE // Default disabled. Uncomment to enable.
// Enable control pin states feedback in status reports. The data is presented as simple binary of
// the control pin port (0 (low) or 1(high)), masked to show only the input pins. Non-control pins on the
// port will always show a 0 value. See cpu_map.h for the pin bitmap. As with the limit pin reporting,
// we do not recommend keeping this option enabled. Try to only use this for setting up a new CNC.
// #define REPORT_CONTROL_PIN_STATE // Default disabled. Uncomment to enable.
// When Grbl powers-cycles or is hard reset with the Arduino reset button, Grbl boots up with no ALARM
// by default. This is to make it as simple as possible for new users to start using Grbl. When homing
// is enabled and a user has installed limit switches, Grbl will boot up in an ALARM state to indicate
// Grbl doesn't know its position and to force the user to home before proceeding. This option forces
// Grbl to always initialize into an ALARM state regardless of homing or not. This option is more for
// OEMs and LinuxCNC users that would like this power-cycle behavior.
// #define FORCE_INITIALIZATION_ALARM // Default disabled. Uncomment to enable.
// --------------------------------------------------------------------------------------- // ---------------------------------------------------------------------------------------
// ADVANCED CONFIGURATION OPTIONS: // ADVANCED CONFIGURATION OPTIONS:
// Enables minimal reporting feedback mode for GUIs, where human-readable strings are not as important.
// This saves nearly 2KB of flash space and may allow enough space to install other/future features.
// GUIs will need to install a look-up table for the error-codes that Grbl sends back in their place.
// NOTE: This feature is new and experimental. Make sure the GUI you are using supports this mode.
// #define REPORT_GUI_MODE // Default disabled. Uncomment to enable.
// The temporal resolution of the acceleration management subsystem. A higher number gives smoother // The temporal resolution of the acceleration management subsystem. A higher number gives smoother
// acceleration, particularly noticeable on machines that run at very high feedrates, but may negatively // acceleration, particularly noticeable on machines that run at very high feedrates, but may negatively
// impact performance. The correct value for this parameter is machine dependent, so it's advised to // impact performance. The correct value for this parameter is machine dependent, so it's advised to
@ -145,6 +202,30 @@
// step smoothing. See stepper.c for more details on the AMASS system works. // step smoothing. See stepper.c for more details on the AMASS system works.
#define ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING // Default enabled. Comment to disable. #define ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING // Default enabled. Comment to disable.
// Sets the maximum step rate allowed to be written as a Grbl setting. This option enables an error
// check in the settings module to prevent settings values that will exceed this limitation. The maximum
// step rate is strictly limited by the CPU speed and will change if something other than an AVR running
// at 16MHz is used.
// NOTE: For now disabled, will enable if flash space permits.
// #define MAX_STEP_RATE_HZ 30000 // Hz
// By default, Grbl sets all input pins to normal-high operation with their internal pull-up resistors
// enabled. This simplifies the wiring for users by requiring only a switch connected to ground,
// although its recommended that users take the extra step of wiring in low-pass filter to reduce
// electrical noise detected by the pin. If the user inverts the pin in Grbl settings, this just flips
// which high or low reading indicates an active signal. In normal operation, this means the user
// needs to connect a normal-open switch, but if inverted, this means the user should connect a
// normal-closed switch.
// The following options disable the internal pull-up resistors, sets the pins to a normal-low
// operation, and switches must be now connect to Vcc instead of ground. This also flips the meaning
// of the invert pin Grbl setting, where an inverted setting now means the user should connect a
// normal-open switch and vice versa.
// NOTE: All pins associated with the feature are disabled, i.e. XYZ limit pins, not individual axes.
// WARNING: When the pull-ups are disabled, this requires additional wiring with pull-down resistors!
//#define DISABLE_LIMIT_PIN_PULL_UP
//#define DISABLE_PROBE_PIN_PULL_UP
//#define DISABLE_CONTROL_PIN_PULL_UP
// Sets which axis the tool length offset is applied. Assumes the spindle is always parallel with // Sets which axis the tool length offset is applied. Assumes the spindle is always parallel with
// the selected axis with the tool oriented toward the negative direction. In other words, a positive // the selected axis with the tool oriented toward the negative direction. In other words, a positive
// tool length offset value is subtracted from the current location. // tool length offset value is subtracted from the current location.
@ -154,9 +235,9 @@
// enable pin will output 5V for maximum RPM with 256 intermediate levels and 0V when disabled. // enable pin will output 5V for maximum RPM with 256 intermediate levels and 0V when disabled.
// NOTE: IMPORTANT for Arduino Unos! When enabled, the Z-limit pin D11 and spindle enable pin D12 switch! // NOTE: IMPORTANT for Arduino Unos! When enabled, the Z-limit pin D11 and spindle enable pin D12 switch!
// The hardware PWM output on pin D11 is required for variable spindle output voltages. // The hardware PWM output on pin D11 is required for variable spindle output voltages.
// #define VARIABLE_SPINDLE // Default disabled. Uncomment to enable. #define VARIABLE_SPINDLE // Default enabled. Comment to disable.
// Use by the variable spindle output only. These parameters set the maximum and minimum spindle speed // Used by the variable spindle output only. These parameters set the maximum and minimum spindle speed
// "S" g-code values to correspond to the maximum and minimum pin voltages. There are 256 discrete and // "S" g-code values to correspond to the maximum and minimum pin voltages. There are 256 discrete and
// equally divided voltage bins between the maximum and minimum spindle speeds. So for a 5V pin, 1000 // equally divided voltage bins between the maximum and minimum spindle speeds. So for a 5V pin, 1000
// max rpm, and 250 min rpm, the spindle output voltage would be set for the following "S" commands: // max rpm, and 250 min rpm, the spindle output voltage would be set for the following "S" commands:
@ -164,6 +245,12 @@
#define SPINDLE_MAX_RPM 1000.0 // Max spindle RPM. This value is equal to 100% duty cycle on the PWM. #define SPINDLE_MAX_RPM 1000.0 // Max spindle RPM. This value is equal to 100% duty cycle on the PWM.
#define SPINDLE_MIN_RPM 0.0 // Min spindle RPM. This value is equal to (1/256) duty cycle on the PWM. #define SPINDLE_MIN_RPM 0.0 // Min spindle RPM. This value is equal to (1/256) duty cycle on the PWM.
// Used by variable spindle output only. This forces the PWM output to a minimum duty cycle when enabled.
// When disabled, the PWM pin will still read 0V. Most users will not need this option, but it may be
// useful in certain scenarios. This setting does not update the minimum spindle RPM calculations. Any
// spindle RPM output lower than this value will be set to this value.
// #define MINIMUM_SPINDLE_PWM 5 // Default disabled. Uncomment to enable. Integer (0-255)
// Minimum planner junction speed. Sets the default minimum junction speed the planner plans to at // Minimum planner junction speed. Sets the default minimum junction speed the planner plans to at
// every buffer block junction, except for starting from rest and end of the buffer, which are always // every buffer block junction, except for starting from rest and end of the buffer, which are always
// zero. This value controls how fast the machine moves through junctions with no regard for acceleration // zero. This value controls how fast the machine moves through junctions with no regard for acceleration
@ -255,6 +342,17 @@
// work well and are cheap to find) and wire in a low-pass circuit into each limit pin. // work well and are cheap to find) and wire in a low-pass circuit into each limit pin.
// #define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable. // #define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
// Force Grbl to check the state of the hard limit switches when the processor detects a pin
// change inside the hard limit ISR routine. By default, Grbl will trigger the hard limits
// alarm upon any pin change, since bouncing switches can cause a state check like this to
// misread the pin. When hard limits are triggers, this should be 100% reliable, which is the
// reason that this option is disabled by default. Only if your system/electronics can guarantee
// the pins don't bounce, we recommend enabling this option. If so, this will help prevent
// triggering a hard limit when the machine disengages from the switch.
// NOTE: This option has no effect if SOFTWARE_DEBOUNCE is enabled.
// #define HARD_LIMIT_FORCE_STATE_CHECK // Default disabled. Uncomment to enable.
// --------------------------------------------------------------------------------------- // ---------------------------------------------------------------------------------------
// TODO: Install compile-time option to send numeric status codes rather than strings. // TODO: Install compile-time option to send numeric status codes rather than strings.
@ -262,9 +360,7 @@
// --------------------------------------------------------------------------------------- // ---------------------------------------------------------------------------------------
// COMPILE-TIME ERROR CHECKING OF DEFINE VALUES: // COMPILE-TIME ERROR CHECKING OF DEFINE VALUES:
// #if (ISR_TICKS_PER_ACCELERATION_TICK > 255)
// #error Parameters ACCELERATION_TICKS / ISR_TICKS must be < 256 to prevent integer overflow.
// #endif
// --------------------------------------------------------------------------------------- // ---------------------------------------------------------------------------------------

View File

@ -1,8 +1,8 @@
/* /*
coolant_control.c - coolant control methods coolant_control.c - coolant control methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -18,10 +18,7 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "system.h" #include "grbl.h"
#include "coolant_control.h"
#include "protocol.h"
#include "gcode.h"
void coolant_init() void coolant_init()
@ -43,12 +40,8 @@ void coolant_stop()
} }
void coolant_run(uint8_t mode) void coolant_set_state(uint8_t mode)
{ {
if (sys.state == STATE_CHECK_MODE) { return; }
protocol_auto_cycle_start(); //temp fix for M8 lockup
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
if (mode == COOLANT_FLOOD_ENABLE) { if (mode == COOLANT_FLOOD_ENABLE) {
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT); COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
@ -61,3 +54,11 @@ void coolant_run(uint8_t mode)
coolant_stop(); coolant_stop();
} }
} }
void coolant_run(uint8_t mode)
{
if (sys.state == STATE_CHECK_MODE) { return; }
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
coolant_set_state(mode);
}

View File

@ -1,8 +1,8 @@
/* /*
coolant_control.h - spindle control methods coolant_control.h - spindle control methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -24,6 +24,7 @@
void coolant_init(); void coolant_init();
void coolant_stop(); void coolant_stop();
void coolant_set_state(uint8_t mode);
void coolant_run(uint8_t mode); void coolant_run(uint8_t mode);
#endif #endif

View File

@ -1,8 +1,8 @@
/* /*
cpu_map.h - CPU and pin mapping configuration file cpu_map.h - CPU and pin mapping configuration file
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -31,7 +31,7 @@
//---------------------------------------------------------------------------------------- //----------------------------------------------------------------------------------------
#ifdef CPU_MAP_ATMEGA328P_TRADITIONAL // (Arduino Uno) Officially supported by Grbl. #ifdef CPU_MAP_ATMEGA328P // (Arduino Uno) Officially supported by Grbl.
// Define serial port pins and interrupt vectors. // Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect #define SERIAL_RX USART_RX_vect
@ -60,7 +60,7 @@
#define STEPPERS_DISABLE_MASK (1<<STEPPERS_DISABLE_BIT) #define STEPPERS_DISABLE_MASK (1<<STEPPERS_DISABLE_BIT)
// Define homing/hard limit switch input pins and limit interrupt vectors. // Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (pinout). // NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
#define LIMIT_DDR DDRB #define LIMIT_DDR DDRB
#define LIMIT_PIN PINB #define LIMIT_PIN PINB
#define LIMIT_PORT PORTB #define LIMIT_PORT PORTB
@ -100,18 +100,19 @@
#define COOLANT_MIST_BIT 4 // Uno Analog Pin 4 #define COOLANT_MIST_BIT 4 // Uno Analog Pin 4
#endif #endif
// Define user-control pinouts (cycle start, reset, feed hold) input pins. // Define user-control controls (cycle start, reset, feed hold) input pins.
// NOTE: All pinouts pins must be on the same port and not on a port with other input pins (limits). // NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define PINOUT_DDR DDRC #define CONTROL_DDR DDRC
#define PINOUT_PIN PINC #define CONTROL_PIN PINC
#define PINOUT_PORT PORTC #define CONTROL_PORT PORTC
#define PIN_RESET 0 // Uno Analog Pin 0 #define RESET_BIT 0 // Uno Analog Pin 0
#define PIN_FEED_HOLD 1 // Uno Analog Pin 1 #define FEED_HOLD_BIT 1 // Uno Analog Pin 1
#define PIN_CYCLE_START 2 // Uno Analog Pin 2 #define CYCLE_START_BIT 2 // Uno Analog Pin 2
#define PINOUT_INT PCIE1 // Pin change interrupt enable pin #define SAFETY_DOOR_BIT 1 // Uno Analog Pin 1 NOTE: Safety door is shared with feed hold. Enabled by config define.
#define PINOUT_INT_vect PCINT1_vect #define CONTROL_INT PCIE1 // Pin change interrupt enable pin
#define PINOUT_PCMSK PCMSK1 // Pin change interrupt register #define CONTROL_INT_vect PCINT1_vect
#define PINOUT_MASK ((1<<PIN_RESET)|(1<<PIN_FEED_HOLD)|(1<<PIN_CYCLE_START)) #define CONTROL_PCMSK PCMSK1 // Pin change interrupt register
#define CONTROL_MASK ((1<<RESET_BIT)|(1<<FEED_HOLD_BIT)|(1<<CYCLE_START_BIT)|(1<<SAFETY_DOOR_BIT))
// Define probe switch input pin. // Define probe switch input pin.
#define PROBE_DDR DDRC #define PROBE_DDR DDRC
@ -123,6 +124,7 @@
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
// Advanced Configuration Below You should not need to touch these variables // Advanced Configuration Below You should not need to touch these variables
#define PWM_MAX_VALUE 255.0
#define TCCRA_REGISTER TCCR2A #define TCCRA_REGISTER TCCR2A
#define TCCRB_REGISTER TCCR2B #define TCCRB_REGISTER TCCR2B
#define OCR_REGISTER OCR2A #define OCR_REGISTER OCR2A
@ -142,118 +144,6 @@
#endif #endif
//----------------------------------------------------------------------------------------
#ifdef CPU_MAP_ATMEGA328P_NEW // (Arduino Uno) New test pinout configuration. Still subject to change. Not finalized!
// Define serial port pins and interrupt vectors.
#define SERIAL_RX USART_RX_vect
#define SERIAL_UDRE USART_UDRE_vect
// Define step pulse output pins. NOTE: All step bit pins must be on the same port.
#define STEP_DDR DDRD
#define STEP_PORT PORTD
#define X_STEP_BIT 2 // Uno Digital Pin 2
#define Y_STEP_BIT 3 // Uno Digital Pin 3
#define Z_STEP_BIT 4 // Uno Digital Pin 4
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR DDRD
#define DIRECTION_PORT PORTD
#define X_DIRECTION_BIT 5 // Uno Digital Pin 5
#define Y_DIRECTION_BIT 6 // Uno Digital Pin 6
#define Z_DIRECTION_BIT 7 // Uno Digital Pin 7
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin.
#define STEPPERS_DISABLE_DDR DDRB
#define STEPPERS_DISABLE_PORT PORTB
#define STEPPERS_DISABLE_BIT 0 // Uno Digital Pin 8
#define STEPPERS_DISABLE_MASK (1<<STEPPERS_DISABLE_BIT)
// Define homing/hard limit switch input pins and limit interrupt vectors.
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (pinout).
#define LIMIT_DDR DDRB
#define LIMIT_PIN PINB
#define LIMIT_PORT PORTB
#define X_LIMIT_BIT 1 // Uno Digital Pin 9
#define Y_LIMIT_BIT 2 // Uno Digital Pin 10
#ifdef VARIABLE_SPINDLE // Z Limit pin and spindle enabled swapped to access hardware PWM on Pin 11.
#define Z_LIMIT_BIT 4 // Uno Digital Pin 12
#else
#define Z_LIMIT_BIT 3 // Uno Digital Pin 11
#endif
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)) // All limit bits
#define LIMIT_INT PCIE0 // Pin change interrupt enable pin
#define LIMIT_INT_vect PCINT0_vect
#define LIMIT_PCMSK PCMSK0 // Pin change interrupt register
// Define spindle enable and spindle direction output pins.
#define SPINDLE_ENABLE_DDR DDRB
#define SPINDLE_ENABLE_PORT PORTB
#ifdef VARIABLE_SPINDLE // Z Limit pin and spindle enabled swapped to access hardware PWM on Pin 11.
#define SPINDLE_ENABLE_BIT 3 // Uno Digital Pin 11
#else
#define SPINDLE_ENABLE_BIT 4 // Uno Digital Pin 12
#endif
#define SPINDLE_DIRECTION_DDR DDRB
#define SPINDLE_DIRECTION_PORT PORTB
#define SPINDLE_DIRECTION_BIT 5 // Uno Digital Pin 13 (NOTE: D13 can't be pulled-high input due to LED.)
// Define flood and mist coolant enable output pins.
// NOTE: Uno analog pins 4 and 5 are reserved for an i2c interface, and may be installed at
// a later date if flash and memory space allows.
#define COOLANT_FLOOD_DDR DDRC
#define COOLANT_FLOOD_PORT PORTC
#define COOLANT_FLOOD_BIT 4 // Uno Analog Pin 3
#ifdef ENABLE_M7 // Mist coolant disabled by default. See config.h to enable/disable.
#define COOLANT_MIST_DDR DDRC
#define COOLANT_MIST_PORT PORTC
#define COOLANT_MIST_BIT 5 // Uno Analog Pin 4
#endif
// Define user-control pinouts (cycle start, reset, feed hold) input pins.
// NOTE: All pinouts pins must be on the same port and not on a port with other input pins (limits).
#define PINOUT_DDR DDRC
#define PINOUT_PIN PINC
#define PINOUT_PORT PORTC
#define PIN_RESET 1 // Uno Analog Pin 1
#define PIN_FEED_HOLD 2 // Uno Analog Pin 2
#define PIN_CYCLE_START 3 // Uno Analog Pin 3
#define PINOUT_INT PCIE1 // Pin change interrupt enable pin
#define PINOUT_INT_vect PCINT1_vect
#define PINOUT_PCMSK PCMSK1 // Pin change interrupt register
#define PINOUT_MASK ((1<<PIN_RESET)|(1<<PIN_FEED_HOLD)|(1<<PIN_CYCLE_START))
// Define probe switch input pin.
#define PROBE_DDR DDRC
#define PROBE_PIN PINC
#define PROBE_PORT PORTC
#define PROBE_BIT 0 // Uno Analog Pin 0
#define PROBE_MASK (1<<PROBE_BIT)
#ifdef VARIABLE_SPINDLE
// Advanced Configuration Below You should not need to touch these variables
#define TCCRA_REGISTER TCCR2A
#define TCCRB_REGISTER TCCR2B
#define OCR_REGISTER OCR2A
#define COMB_BIT COM2A1
#define WAVE0_REGISTER WGM20
#define WAVE1_REGISTER WGM21
#define WAVE2_REGISTER WGM22
#define WAVE3_REGISTER WGM23
// NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings.
#define SPINDLE_PWM_DDR SPINDLE_ENABLE_DDR
#define SPINDLE_PWM_PORT SPINDLE_ENABLE_PORT
#define SPINDLE_PWM_BIT SPINDLE_ENABLE_BIT // Shared with SPINDLE_ENABLE.
#endif // End of VARIABLE_SPINDLE
#endif
//---------------------------------------------------------------------------------------- //----------------------------------------------------------------------------------------
#ifdef CPU_MAP_ATMEGA2560 // (Arduino Mega 2560) Working @EliteEng #ifdef CPU_MAP_ATMEGA2560 // (Arduino Mega 2560) Working @EliteEng
@ -272,18 +162,18 @@
#define STEP_DDR DDRA #define STEP_DDR DDRA
#define STEP_PORT PORTA #define STEP_PORT PORTA
#define STEP_PIN PINA #define STEP_PIN PINA
#define X_STEP_BIT 2 // MEGA2560 Digital Pin 24 #define X_STEP_BIT 2 // MEGA2560 Digital Pin 24
#define Y_STEP_BIT 3 // MEGA2560 Digital Pin 25 #define Y_STEP_BIT 3 // MEGA2560 Digital Pin 25
#define Z_STEP_BIT 4 // MEGA2560 Digital Pin 26 #define Z_STEP_BIT 4 // MEGA2560 Digital Pin 26
#define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)) // All step bits #define STEP_MASK ((1<<X_STEP_BIT)|(1<<Y_STEP_BIT)|(1<<Z_STEP_BIT)) // All step bits
// Define step direction output pins. NOTE: All direction pins must be on the same port. // Define step direction output pins. NOTE: All direction pins must be on the same port.
#define DIRECTION_DDR DDRA #define DIRECTION_DDR DDRC
#define DIRECTION_PORT PORTA #define DIRECTION_PORT PORTC
#define DIRECTION_PIN PINA #define DIRECTION_PIN PINC
#define X_DIRECTION_BIT 5 // MEGA2560 Digital Pin 27 #define X_DIRECTION_BIT 7 // MEGA2560 Digital Pin 30
#define Y_DIRECTION_BIT 6 // MEGA2560 Digital Pin 28 #define Y_DIRECTION_BIT 6 // MEGA2560 Digital Pin 31
#define Z_DIRECTION_BIT 7 // MEGA2560 Digital Pin 29 #define Z_DIRECTION_BIT 5 // MEGA2560 Digital Pin 32
#define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)) // All direction bits #define DIRECTION_MASK ((1<<X_DIRECTION_BIT)|(1<<Y_DIRECTION_BIT)|(1<<Z_DIRECTION_BIT)) // All direction bits
// Define stepper driver enable/disable output pin. // Define stepper driver enable/disable output pin.
@ -305,9 +195,9 @@
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)) // All limit bits #define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)) // All limit bits
// Define spindle enable and spindle direction output pins. // Define spindle enable and spindle direction output pins.
#define SPINDLE_ENABLE_DDR DDRH #define SPINDLE_ENABLE_DDR DDRH
#define SPINDLE_ENABLE_PORT PORTH #define SPINDLE_ENABLE_PORT PORTH
#define SPINDLE_ENABLE_BIT 3 // MEGA2560 Digital Pin 6 #define SPINDLE_ENABLE_BIT 3 // MEGA2560 Digital Pin 6
#define SPINDLE_DIRECTION_DDR DDRE #define SPINDLE_DIRECTION_DDR DDRE
#define SPINDLE_DIRECTION_PORT PORTE #define SPINDLE_DIRECTION_PORT PORTE
#define SPINDLE_DIRECTION_BIT 3 // MEGA2560 Digital Pin 5 #define SPINDLE_DIRECTION_BIT 3 // MEGA2560 Digital Pin 5
@ -315,52 +205,54 @@
// Define flood and mist coolant enable output pins. // Define flood and mist coolant enable output pins.
// NOTE: Uno analog pins 4 and 5 are reserved for an i2c interface, and may be installed at // NOTE: Uno analog pins 4 and 5 are reserved for an i2c interface, and may be installed at
// a later date if flash and memory space allows. // a later date if flash and memory space allows.
#define COOLANT_FLOOD_DDR DDRH #define COOLANT_FLOOD_DDR DDRH
#define COOLANT_FLOOD_PORT PORTH #define COOLANT_FLOOD_PORT PORTH
#define COOLANT_FLOOD_BIT 5 // MEGA2560 Digital Pin 8 #define COOLANT_FLOOD_BIT 5 // MEGA2560 Digital Pin 8
#ifdef ENABLE_M7 // Mist coolant disabled by default. See config.h to enable/disable. #ifdef ENABLE_M7 // Mist coolant disabled by default. See config.h to enable/disable.
#define COOLANT_MIST_DDR DDRH #define COOLANT_MIST_DDR DDRH
#define COOLANT_MIST_PORT PORTH #define COOLANT_MIST_PORT PORTH
#define COOLANT_MIST_BIT 6 // MEGA2560 Digital Pin 9 #define COOLANT_MIST_BIT 6 // MEGA2560 Digital Pin 9
#endif #endif
// Define user-control pinouts (cycle start, reset, feed hold) input pins. // Define user-control CONTROLs (cycle start, reset, feed hold) input pins.
// NOTE: All pinouts pins must be on the same port and not on a port with other input pins (limits). // NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
#define PINOUT_DDR DDRK #define CONTROL_DDR DDRK
#define PINOUT_PIN PINK #define CONTROL_PIN PINK
#define PINOUT_PORT PORTK #define CONTROL_PORT PORTK
#define PIN_RESET 0 // MEGA2560 Analog Pin 8 #define RESET_BIT 0 // MEGA2560 Analog Pin 8
#define PIN_FEED_HOLD 1 // MEGA2560 Analog Pin 9 #define FEED_HOLD_BIT 1 // MEGA2560 Analog Pin 9
#define PIN_CYCLE_START 2 // MEGA2560 Analog Pin 10 #define CYCLE_START_BIT 2 // MEGA2560 Analog Pin 10
#define PINOUT_INT PCIE2 // Pin change interrupt enable pin #define SAFETY_DOOR_BIT 3 // MEGA2560 Analog Pin 11
#define PINOUT_INT_vect PCINT2_vect #define CONTROL_INT PCIE2 // Pin change interrupt enable pin
#define PINOUT_PCMSK PCMSK2 // Pin change interrupt register #define CONTROL_INT_vect PCINT2_vect
#define PINOUT_MASK ((1<<PIN_RESET)|(1<<PIN_FEED_HOLD)|(1<<PIN_CYCLE_START)) #define CONTROL_PCMSK PCMSK2 // Pin change interrupt register
#define CONTROL_MASK ((1<<RESET_BIT)|(1<<FEED_HOLD_BIT)|(1<<CYCLE_START_BIT)|(1<<SAFETY_DOOR_BIT))
// Define probe switch input pin. // Define probe switch input pin.
#define PROBE_DDR DDRK #define PROBE_DDR DDRK
#define PROBE_PIN PINK #define PROBE_PIN PINK
#define PROBE_PORT PORTK #define PROBE_PORT PORTK
#define PROBE_BIT 3 // MEGA2560 Analog Pin 11 #define PROBE_BIT 7 // MEGA2560 Analog Pin 15
#define PROBE_MASK (1<<PROBE_BIT) #define PROBE_MASK (1<<PROBE_BIT)
// Start of PWM & Stepper Enabled Spindle // Start of PWM & Stepper Enabled Spindle
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
// Advanced Configuration Below You should not need to touch these variables // Advanced Configuration Below You should not need to touch these variables
// Set Timer up to use TIMER2B which is attached to Digital Pin 9 // Set Timer up to use TIMER4B which is attached to Digital Pin 7
#define TCCRA_REGISTER TCCR2A #define PWM_MAX_VALUE 65535.0
#define TCCRB_REGISTER TCCR2B #define TCCRA_REGISTER TCCR4A
#define OCR_REGISTER OCR2B #define TCCRB_REGISTER TCCR4B
#define OCR_REGISTER OCR4B
#define COMB_BIT COM2B1 #define COMB_BIT COM4B1
#define WAVE0_REGISTER WGM20 #define WAVE0_REGISTER WGM40
#define WAVE1_REGISTER WGM21 #define WAVE1_REGISTER WGM41
#define WAVE2_REGISTER WGM22 #define WAVE2_REGISTER WGM42
#define WAVE3_REGISTER WGM23 #define WAVE3_REGISTER WGM43
#define SPINDLE_PWM_DDR DDRH #define SPINDLE_PWM_DDR DDRH
#define SPINDLE_PWM_PORT PORTH #define SPINDLE_PWM_PORT PORTH
#define SPINDLE_PWM_BIT 6 // MEGA2560 Digital Pin 9 #define SPINDLE_PWM_BIT 4 // MEGA2560 Digital Pin 97
#endif // End of VARIABLE_SPINDLE #endif // End of VARIABLE_SPINDLE
#endif #endif

View File

@ -1,8 +1,8 @@
/* /*
defaults.h - defaults settings configuration file defaults.h - defaults settings configuration file
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -43,7 +43,7 @@
#define DEFAULT_Z_MAX_TRAVEL 200.0 // mm #define DEFAULT_Z_MAX_TRAVEL 200.0 // mm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10 #define DEFAULT_STEP_PULSE_MICROSECONDS 10
#define DEFAULT_STEPPING_INVERT_MASK 0 #define DEFAULT_STEPPING_INVERT_MASK 0
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<Y_AXIS)|(1<<Z_AXIS)) #define DEFAULT_DIRECTION_INVERT_MASK 0
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled) #define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION)) #define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm #define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
@ -263,4 +263,40 @@
#define DEFAULT_HOMING_PULLOFF 1.0 // mm #define DEFAULT_HOMING_PULLOFF 1.0 // mm
#endif #endif
#ifdef DEFAULTS_SIMULATOR
// Settings only for Grbl Simulator (www.github.com/grbl/grbl-sim)
// Grbl generic default settings. Should work across different machines.
#define DEFAULT_X_STEPS_PER_MM 1000.0
#define DEFAULT_Y_STEPS_PER_MM 1000.0
#define DEFAULT_Z_STEPS_PER_MM 1000.0
#define DEFAULT_X_MAX_RATE 1000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 1000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 1000.0 // mm/min
#define DEFAULT_X_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_X_MAX_TRAVEL 1000.0 // mm
#define DEFAULT_Y_MAX_TRAVEL 1000.0 // mm
#define DEFAULT_Z_MAX_TRAVEL 1000.0 // mm
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
#define DEFAULT_STEPPING_INVERT_MASK 0
#define DEFAULT_DIRECTION_INVERT_MASK 0
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_AUTO_START 1 // true
#define DEFAULT_INVERT_ST_ENABLE 0 // false
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_HOMING_ENABLE 0 // false
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 500.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
#endif
#endif #endif

29
grbl/eeprom.h Normal file
View File

@ -0,0 +1,29 @@
/*
eeprom.h - EEPROM methods
Part of Grbl
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef eeprom_h
#define eeprom_h
unsigned char eeprom_get_char(unsigned int addr);
void eeprom_put_char(unsigned int addr, unsigned char new_value);
void memcpy_to_eeprom_with_checksum(unsigned int destination, char *source, unsigned int size);
int memcpy_from_eeprom_with_checksum(char *destination, unsigned int source, unsigned int size);
#endif

View File

@ -0,0 +1,29 @@
/***********************************************************************
This sketch compiles and uploads Grbl to your 328p-based Arduino!
To use:
- First make sure you have imported Grbl source code into your Arduino
IDE. There are details on our Github website on how to do this.
- Select your Arduino Board and Serial Port in the Tools drop-down menu.
NOTE: Grbl only officially supports 328p-based Arduinos, like the Uno.
Using other boards will likely not work!
- Then just click 'Upload'. That's it!
For advanced users:
If you'd like to see what else Grbl can do, there are some additional
options for customization and features you can enable or disable.
Navigate your file system to where the Arduino IDE has stored the Grbl
source code files, open the 'config.h' file in your favorite text
editor. Inside are dozens of feature descriptions and #defines. Simply
comment or uncomment the #defines or alter their assigned values, save
your changes, and then click 'Upload' here.
Copyright (c) 2015 Sungeun K. Jeon
Released under the MIT-license. See license.txt for details.
***********************************************************************/
#include <grbl.h>
// Do not alter this file!

View File

@ -0,0 +1,21 @@
The MIT License (MIT)
Copyright (c) 2015 Sungeun K. Jeon
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.

View File

@ -1,8 +1,9 @@
/* /*
gcode.c - rs274/ngc parser. gcode.c - rs274/ngc parser.
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,22 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "settings.h"
#include "protocol.h"
#include "gcode.h"
#include "motion_control.h"
#include "spindle_control.h"
#include "coolant_control.h"
#include "probe.h"
#include "report.h"
// NOTE: Max line number is defined by the g-code standard to be 99999. It seems to be an // NOTE: Max line number is defined by the g-code standard to be 99999. It seems to be an
// arbitrary value, and some GUIs may require more. So we increased it based on a max safe // arbitrary value, and some GUIs may require more. So we increased it based on a max safe
@ -66,10 +53,7 @@ void gc_init()
// limit pull-off routines. // limit pull-off routines.
void gc_sync_position() void gc_sync_position()
{ {
uint8_t i; system_convert_array_steps_to_mpos(gc_state.position,sys.position);
for (i=0; i<N_AXIS; i++) {
gc_state.position[i] = sys.position[i]/settings.steps_per_mm[i];
}
} }
@ -123,8 +107,7 @@ uint8_t gc_execute_line(char *line)
char letter; char letter;
float value; float value;
uint8_t int_value = 0; uint8_t int_value = 0;
uint8_t mantissa = 0; // NOTE: For mantissa values > 255, variable type must be changed to uint16_t. uint16_t mantissa = 0;
while (line[char_counter] != 0) { // Loop until no more g-code words in line. while (line[char_counter] != 0) { // Loop until no more g-code words in line.
@ -210,11 +193,10 @@ uint8_t gc_execute_line(char *line)
case 3: gc_block.modal.motion = MOTION_MODE_CCW_ARC; break; // G3 case 3: gc_block.modal.motion = MOTION_MODE_CCW_ARC; break; // G3
case 38: case 38:
switch(mantissa) { switch(mantissa) {
case 20: gc_block.modal.motion = MOTION_MODE_PROBE; break; // G38.2 case 20: gc_block.modal.motion = MOTION_MODE_PROBE_TOWARD; break; // G38.2
// NOTE: If G38.3+ are enabled, change mantissa variable type to uint16_t. case 30: gc_block.modal.motion = MOTION_MODE_PROBE_TOWARD_NO_ERROR; break; // G38.3
// case 30: gc_block.modal.motion = MOTION_MODE_PROBE_NO_ERROR; break; // G38.3 Not supported. case 40: gc_block.modal.motion = MOTION_MODE_PROBE_AWAY; break; // G38.4
// case 40: // Not supported. case 50: gc_block.modal.motion = MOTION_MODE_PROBE_AWAY_NO_ERROR; break; // G38.5
// case 50: // Not supported.
default: FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported G38.x command] default: FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported G38.x command]
} }
mantissa = 0; // Set to zero to indicate valid non-integer G command. mantissa = 0; // Set to zero to indicate valid non-integer G command.
@ -231,9 +213,16 @@ uint8_t gc_execute_line(char *line)
} }
break; break;
case 90: case 91: case 90: case 91:
word_bit = MODAL_GROUP_G3; if (mantissa == 0) {
if (int_value == 90) { gc_block.modal.distance = DISTANCE_MODE_ABSOLUTE; } // G90 word_bit = MODAL_GROUP_G3;
else { gc_block.modal.distance = DISTANCE_MODE_INCREMENTAL; } // G91 if (int_value == 90) { gc_block.modal.distance = DISTANCE_MODE_ABSOLUTE; } // G90
else { gc_block.modal.distance = DISTANCE_MODE_INCREMENTAL; } // G91
} else {
word_bit = MODAL_GROUP_G4;
if (mantissa != 10) { FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); } // [G90.1 not supported]
mantissa = 0; // Set to zero to indicate valid non-integer G command.
// Otherwise, arc IJK incremental mode is default. G91.1 does nothing.
}
break; break;
case 93: case 94: case 93: case 94:
word_bit = MODAL_GROUP_G5; word_bit = MODAL_GROUP_G5;
@ -245,6 +234,12 @@ uint8_t gc_execute_line(char *line)
if (int_value == 20) { gc_block.modal.units = UNITS_MODE_INCHES; } // G20 if (int_value == 20) { gc_block.modal.units = UNITS_MODE_INCHES; } // G20
else { gc_block.modal.units = UNITS_MODE_MM; } // G21 else { gc_block.modal.units = UNITS_MODE_MM; } // G21
break; break;
case 40:
word_bit = MODAL_GROUP_G7;
// NOTE: Not required since cutter radius compensation is always disabled. Only here
// to support G40 commands that often appear in g-code program headers to setup defaults.
// gc_block.modal.cutter_comp = CUTTER_COMP_DISABLE; // G40
break;
case 43: case 49: case 43: case 49:
word_bit = MODAL_GROUP_G8; word_bit = MODAL_GROUP_G8;
// NOTE: The NIST g-code standard vaguely states that when a tool length offset is changed, // NOTE: The NIST g-code standard vaguely states that when a tool length offset is changed,
@ -490,7 +485,10 @@ uint8_t gc_execute_line(char *line)
} }
} }
// [13. Cutter radius compensation ]: NOT SUPPORTED. Error, if G53 is active. // [13. Cutter radius compensation ]: G41/42 NOT SUPPORTED. Error, if enabled while G53 is active.
// [G40 Errors]: G2/3 arc is programmed after a G40. The linear move after disabling is less than tool diameter.
// NOTE: Since cutter radius compensation is never enabled, these G40 errors don't apply. Grbl supports G40
// only for the purpose to not error when G40 is sent with a g-code program header to setup the default modes.
// [14. Cutter length compensation ]: G43 NOT SUPPORTED, but G43.1 and G49 are. // [14. Cutter length compensation ]: G43 NOT SUPPORTED, but G43.1 and G49 are.
// [G43.1 Errors]: Motion command in same line. // [G43.1 Errors]: Motion command in same line.
@ -800,7 +798,8 @@ uint8_t gc_execute_line(char *line)
} }
} }
break; break;
case MOTION_MODE_PROBE: case MOTION_MODE_PROBE_TOWARD: case MOTION_MODE_PROBE_TOWARD_NO_ERROR:
case MOTION_MODE_PROBE_AWAY: case MOTION_MODE_PROBE_AWAY_NO_ERROR:
// [G38 Errors]: Target is same current. No axis words. Cutter compensation is enabled. Feed rate // [G38 Errors]: Target is same current. No axis words. Cutter compensation is enabled. Feed rate
// is undefined. Probe is triggered. NOTE: Probe check moved to probe cycle. Instead of returning // is undefined. Probe is triggered. NOTE: Probe check moved to probe cycle. Instead of returning
// an error, it issues an alarm to prevent further motion to the probe. It's also done there to // an error, it issues an alarm to prevent further motion to the probe. It's also done there to
@ -827,6 +826,9 @@ uint8_t gc_execute_line(char *line)
need to update the state and execute the block according to the order-of-execution. need to update the state and execute the block according to the order-of-execution.
*/ */
// [0. Non-specific/common error-checks and miscellaneous setup]:
gc_state.line_number = gc_block.values.n;
// [1. Comments feedback ]: NOT SUPPORTED // [1. Comments feedback ]: NOT SUPPORTED
// [2. Set feed rate mode ]: // [2. Set feed rate mode ]:
@ -837,10 +839,9 @@ uint8_t gc_execute_line(char *line)
// [4. Set spindle speed ]: // [4. Set spindle speed ]:
if (gc_state.spindle_speed != gc_block.values.s) { if (gc_state.spindle_speed != gc_block.values.s) {
gc_state.spindle_speed = gc_block.values.s;
// Update running spindle only if not in check mode and not already enabled. // Update running spindle only if not in check mode and not already enabled.
if (gc_state.modal.spindle != SPINDLE_DISABLE) { spindle_run(gc_state.modal.spindle, gc_state.spindle_speed); } if (gc_state.modal.spindle != SPINDLE_DISABLE) { spindle_run(gc_state.modal.spindle, gc_block.values.s); }
gc_state.spindle_speed = gc_block.values.s;
} }
// [5. Select tool ]: NOT SUPPORTED. Only tracks tool value. // [5. Select tool ]: NOT SUPPORTED. Only tracks tool value.
@ -850,15 +851,15 @@ uint8_t gc_execute_line(char *line)
// [7. Spindle control ]: // [7. Spindle control ]:
if (gc_state.modal.spindle != gc_block.modal.spindle) { if (gc_state.modal.spindle != gc_block.modal.spindle) {
gc_state.modal.spindle = gc_block.modal.spindle;
// Update spindle control and apply spindle speed when enabling it in this block. // Update spindle control and apply spindle speed when enabling it in this block.
spindle_run(gc_state.modal.spindle, gc_state.spindle_speed); spindle_run(gc_block.modal.spindle, gc_state.spindle_speed);
gc_state.modal.spindle = gc_block.modal.spindle;
} }
// [8. Coolant control ]: // [8. Coolant control ]:
if (gc_state.modal.coolant != gc_block.modal.coolant) { if (gc_state.modal.coolant != gc_block.modal.coolant) {
coolant_run(gc_block.modal.coolant);
gc_state.modal.coolant = gc_block.modal.coolant; gc_state.modal.coolant = gc_block.modal.coolant;
coolant_run(gc_state.modal.coolant);
} }
// [9. Enable/disable feed rate or spindle overrides ]: NOT SUPPORTED // [9. Enable/disable feed rate or spindle overrides ]: NOT SUPPORTED
@ -872,7 +873,8 @@ uint8_t gc_execute_line(char *line)
// [12. Set length units ]: // [12. Set length units ]:
gc_state.modal.units = gc_block.modal.units; gc_state.modal.units = gc_block.modal.units;
// [13. Cutter radius compensation ]: NOT SUPPORTED // [13. Cutter radius compensation ]: G41/42 NOT SUPPORTED
// gc_state.modal.cutter_comp = gc_block.modal.cutter_comp; // NOTE: Not needed since always disabled.
// [14. Cutter length compensation ]: G43.1 and G49 supported. G43 NOT SUPPORTED. // [14. Cutter length compensation ]: G43.1 and G49 supported. G43 NOT SUPPORTED.
// NOTE: If G43 were supported, its operation wouldn't be any different from G43.1 in terms // NOTE: If G43 were supported, its operation wouldn't be any different from G43.1 in terms
@ -912,13 +914,13 @@ uint8_t gc_execute_line(char *line)
// and absolute and incremental modes. // and absolute and incremental modes.
if (axis_command) { if (axis_command) {
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
mc_line(gc_block.values.xyz, -1.0, false, gc_block.values.n); mc_line(gc_block.values.xyz, -1.0, false, gc_state.line_number);
#else #else
mc_line(gc_block.values.xyz, -1.0, false); mc_line(gc_block.values.xyz, -1.0, false);
#endif #endif
} }
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
mc_line(parameter_data, -1.0, false, gc_block.values.n); mc_line(parameter_data, -1.0, false, gc_state.line_number);
#else #else
mc_line(parameter_data, -1.0, false); mc_line(parameter_data, -1.0, false);
#endif #endif
@ -948,41 +950,71 @@ uint8_t gc_execute_line(char *line)
switch (gc_state.modal.motion) { switch (gc_state.modal.motion) {
case MOTION_MODE_SEEK: case MOTION_MODE_SEEK:
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
mc_line(gc_block.values.xyz, -1.0, false, gc_block.values.n); mc_line(gc_block.values.xyz, -1.0, false, gc_state.line_number);
#else #else
mc_line(gc_block.values.xyz, -1.0, false); mc_line(gc_block.values.xyz, -1.0, false);
#endif #endif
break; break;
case MOTION_MODE_LINEAR: case MOTION_MODE_LINEAR:
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
mc_line(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, gc_block.values.n); mc_line(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, gc_state.line_number);
#else #else
mc_line(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate); mc_line(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate);
#endif #endif
break; break;
case MOTION_MODE_CW_ARC: case MOTION_MODE_CCW_ARC: case MOTION_MODE_CW_ARC:
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r, mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r,
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, gc_block.values.n); gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, true, gc_state.line_number);
#else #else
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r, mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r,
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear); gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, true);
#endif #endif
break; break;
case MOTION_MODE_PROBE: case MOTION_MODE_CCW_ARC:
#ifdef USE_LINE_NUMBERS
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r,
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, false, gc_state.line_number);
#else
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r,
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, false);
#endif
break;
case MOTION_MODE_PROBE_TOWARD:
// NOTE: gc_block.values.xyz is returned from mc_probe_cycle with the updated position value. So // NOTE: gc_block.values.xyz is returned from mc_probe_cycle with the updated position value. So
// upon a successful probing cycle, the machine position and the returned value should be the same. // upon a successful probing cycle, the machine position and the returned value should be the same.
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, gc_block.values.n); mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, false, gc_state.line_number);
#else #else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate); mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, false);
#endif
break;
case MOTION_MODE_PROBE_TOWARD_NO_ERROR:
#ifdef USE_LINE_NUMBERS
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, true, gc_state.line_number);
#else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, true);
#endif
break;
case MOTION_MODE_PROBE_AWAY:
#ifdef USE_LINE_NUMBERS
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, false, gc_state.line_number);
#else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, false);
#endif
break;
case MOTION_MODE_PROBE_AWAY_NO_ERROR:
#ifdef USE_LINE_NUMBERS
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, true, gc_state.line_number);
#else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, true);
#endif #endif
} }
// As far as the parser is concerned, the position is now == target. In reality the // As far as the parser is concerned, the position is now == target. In reality the
// motion control system might still be processing the action and the real tool position // motion control system might still be processing the action and the real tool position
// in any intermediate location. // in any intermediate location.
memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz)); // gc.position[] = target[]; memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz)); // gc_state.position[] = gc_block.values.xyz[]
} }
} }
@ -992,12 +1024,14 @@ uint8_t gc_execute_line(char *line)
gc_state.modal.program_flow = gc_block.modal.program_flow; gc_state.modal.program_flow = gc_block.modal.program_flow;
if (gc_state.modal.program_flow) { if (gc_state.modal.program_flow) {
protocol_buffer_synchronize(); // Finish all remaining buffered motions. Program paused when complete. protocol_buffer_synchronize(); // Finish all remaining buffered motions. Program paused when complete.
sys.auto_start = false; // Disable auto cycle start. Forces pause until cycle start issued.
sys.suspend = true;
protocol_execute_realtime(); // Suspend execution. For both program pause or program end.
// If complete, reset to reload defaults (G92.2,G54,G17,G90,G94,M48,G40,M5,M9). Otherwise, // If complete, reset to reload defaults (G92.2,G54,G17,G90,G94,M48,G40,M5,M9). Otherwise,
// re-enable program flow after pause complete, where cycle start will resume the program. // re-enable program flow after pause complete, where cycle start will resume the program.
if (gc_state.modal.program_flow == PROGRAM_FLOW_COMPLETED) { mc_reset(); } if (gc_state.modal.program_flow == PROGRAM_FLOW_COMPLETED) { mc_reset(); }
else { gc_state.modal.program_flow = PROGRAM_FLOW_RUNNING; } else { gc_state.modal.program_flow = PROGRAM_FLOW_RUNNING; } // Resume from program pause.
} }
// TODO: % to denote start of program. Sets auto cycle start? // TODO: % to denote start of program. Sets auto cycle start?
@ -1022,9 +1056,9 @@ uint8_t gc_execute_line(char *line)
group 1 = {G81 - G89} (Motion modes: Canned cycles) group 1 = {G81 - G89} (Motion modes: Canned cycles)
group 4 = {M1} (Optional stop, ignored) group 4 = {M1} (Optional stop, ignored)
group 6 = {M6} (Tool change) group 6 = {M6} (Tool change)
group 7 = {G40, G41, G42} cutter radius compensation group 7 = {G41, G42} cutter radius compensation (G40 is supported)
group 8 = {G43} tool length offset (But G43.1/G94 IS SUPPORTED) group 8 = {G43} tool length offset (G43.1/G49 are supported)
group 8 = {*M7} enable mist coolant group 8 = {*M7} enable mist coolant (* Compile-option)
group 9 = {M48, M49} enable/disable feed and speed override switches group 9 = {M48, M49} enable/disable feed and speed override switches
group 10 = {G98, G99} return mode canned cycles group 10 = {G98, G99} return mode canned cycles
group 13 = {G61, G61.1, G64} path control mode group 13 = {G61, G61.1, G64} path control mode

View File

@ -1,8 +1,9 @@
/* /*
gcode.h - rs274/ngc parser. gcode.h - rs274/ngc parser.
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef gcode_h #ifndef gcode_h
#define gcode_h #define gcode_h
@ -35,21 +30,23 @@
// and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc). // and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
// NOTE: Modal group define values must be sequential and starting from zero. // NOTE: Modal group define values must be sequential and starting from zero.
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal #define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
#define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G38.2,G80] Motion #define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G38.2,G38.3,G38.4,G38.5,G80] Motion
#define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection #define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection
#define MODAL_GROUP_G3 3 // [G90,G91] Distance mode #define MODAL_GROUP_G3 3 // [G90,G91] Distance mode
#define MODAL_GROUP_G5 4 // [G93,G94] Feed rate mode #define MODAL_GROUP_G4 4 // [G91.1] Arc IJK distance mode
#define MODAL_GROUP_G6 5 // [G20,G21] Units #define MODAL_GROUP_G5 5 // [G93,G94] Feed rate mode
#define MODAL_GROUP_G8 6 // [G43,G43.1,G49] Tool length offset #define MODAL_GROUP_G6 6 // [G20,G21] Units
#define MODAL_GROUP_G12 7 // [G54,G55,G56,G57,G58,G59] Coordinate system selection #define MODAL_GROUP_G7 7 // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED.
#define MODAL_GROUP_G8 8 // [G43.1,G49] Tool length offset
#define MODAL_GROUP_G12 9 // [G54,G55,G56,G57,G58,G59] Coordinate system selection
#define MODAL_GROUP_M4 8 // [M0,M1,M2,M30] Stopping #define MODAL_GROUP_M4 10 // [M0,M1,M2,M30] Stopping
#define MODAL_GROUP_M7 9 // [M3,M4,M5] Spindle turning #define MODAL_GROUP_M7 11 // [M3,M4,M5] Spindle turning
#define MODAL_GROUP_M8 10 // [M7,M8,M9] Coolant control #define MODAL_GROUP_M8 12 // [M7,M8,M9] Coolant control
#define OTHER_INPUT_F 11 #define OTHER_INPUT_F 12
#define OTHER_INPUT_S 12 #define OTHER_INPUT_S 13
#define OTHER_INPUT_T 13 #define OTHER_INPUT_T 14
// Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used // Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
// internally by the parser to know which command to execute. // internally by the parser to know which command to execute.
@ -71,8 +68,11 @@
#define MOTION_MODE_LINEAR 1 // G1 #define MOTION_MODE_LINEAR 1 // G1
#define MOTION_MODE_CW_ARC 2 // G2 #define MOTION_MODE_CW_ARC 2 // G2
#define MOTION_MODE_CCW_ARC 3 // G3 #define MOTION_MODE_CCW_ARC 3 // G3
#define MOTION_MODE_PROBE 4 // G38.2 #define MOTION_MODE_PROBE_TOWARD 4 // G38.2 NOTE: G38.2, G38.3, G38.4, G38.5 must be sequential. See report_gcode_modes().
#define MOTION_MODE_NONE 5 // G80 #define MOTION_MODE_PROBE_TOWARD_NO_ERROR 5 // G38.3
#define MOTION_MODE_PROBE_AWAY 6 // G38.4
#define MOTION_MODE_PROBE_AWAY_NO_ERROR 7 // G38.5
#define MOTION_MODE_NONE 8 // G80
// Modal Group G2: Plane select // Modal Group G2: Plane select
#define PLANE_SELECT_XY 0 // G17 (Default: Must be zero) #define PLANE_SELECT_XY 0 // G17 (Default: Must be zero)
@ -83,6 +83,9 @@
#define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero) #define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero)
#define DISTANCE_MODE_INCREMENTAL 1 // G91 #define DISTANCE_MODE_INCREMENTAL 1 // G91
// Modal Group G4: Arc IJK distance mode
#define DISTANCE_ARC_MODE_INCREMENTAL 0 // G91.1 (Default: Must be zero)
// Modal Group M4: Program flow // Modal Group M4: Program flow
#define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero) #define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero)
#define PROGRAM_FLOW_PAUSED 1 // M0, M1 #define PROGRAM_FLOW_PAUSED 1 // M0, M1
@ -96,6 +99,9 @@
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero) #define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
#define UNITS_MODE_INCHES 1 // G20 #define UNITS_MODE_INCHES 1 // G20
// Modal Group G7: Cutter radius compensation mode
#define CUTTER_COMP_DISABLE 0 // G40 (Default: Must be zero)
// Modal Group M7: Spindle control // Modal Group M7: Spindle control
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero) #define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
#define SPINDLE_ENABLE_CW 1 // M3 #define SPINDLE_ENABLE_CW 1 // M3
@ -132,16 +138,18 @@
// NOTE: When this struct is zeroed, the above defines set the defaults for the system. // NOTE: When this struct is zeroed, the above defines set the defaults for the system.
typedef struct { typedef struct {
uint8_t motion; // {G0,G1,G2,G3,G38.2,G80} uint8_t motion; // {G0,G1,G2,G3,G38.2,G80}
uint8_t feed_rate; // {G93,G94} uint8_t feed_rate; // {G93,G94}
uint8_t units; // {G20,G21} uint8_t units; // {G20,G21}
uint8_t distance; // {G90,G91} uint8_t distance; // {G90,G91}
uint8_t plane_select; // {G17,G18,G19} // uint8_t distance_arc; // {G91.1} NOTE: Don't track. Only one supported.
uint8_t tool_length; // {G43.1,G49} uint8_t plane_select; // {G17,G18,G19}
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59} // uint8_t cutter_comp; // {G40} NOTE: Don't track. Only one supported.
uint8_t program_flow; // {M0,M1,M2,M30} uint8_t tool_length; // {G43.1,G49}
uint8_t coolant; // {M7,M8,M9} uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
uint8_t spindle; // {M3,M4,M5} uint8_t program_flow; // {M0,M1,M2,M30}
uint8_t coolant; // {M7,M8,M9}
uint8_t spindle; // {M3,M4,M5}
} gc_modal_t; } gc_modal_t;
typedef struct { typedef struct {
@ -164,6 +172,7 @@ typedef struct {
float spindle_speed; // RPM float spindle_speed; // RPM
float feed_rate; // Millimeters/min float feed_rate; // Millimeters/min
uint8_t tool; // Tracks tool number. NOT USED. uint8_t tool; // Tracks tool number. NOT USED.
int32_t line_number; // Last line number sent
float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code

62
grbl/grbl.h Normal file
View File

@ -0,0 +1,62 @@
/*
grbl.h - main Grbl include file
Part of Grbl
Copyright (c) 2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef grbl_h
#define grbl_h
// Grbl versioning system
#define GRBL_VERSION "0.9i"
#define GRBL_VERSION_BUILD "20150315"
// Define standard libraries used by Grbl.
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <math.h>
#include <inttypes.h>
#include <string.h>
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
// Define the Grbl system include files. NOTE: Do not alter organization.
#include "config.h"
#include "nuts_bolts.h"
#include "settings.h"
#include "system.h"
#include "defaults.h"
#include "cpu_map.h"
#include "coolant_control.h"
#include "eeprom.h"
#include "gcode.h"
#include "limits.h"
#include "motion_control.h"
#include "planner.h"
#include "print.h"
#include "probe.h"
#include "protocol.h"
#include "report.h"
#include "serial.h"
#include "spindle_control.h"
#include "stepper.h"
#endif

View File

@ -1,8 +1,9 @@
/* /*
limits.c - code pertaining to limit-switches and performing the homing cycle limits.c - code pertaining to limit-switches and performing the homing cycle
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,21 +18,9 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "settings.h"
#include "protocol.h"
#include "planner.h"
#include "stepper.h"
#include "motion_control.h"
#include "limits.h"
#include "report.h"
// Homing axis search distance multiplier. Computed by this value times the axis max travel. // Homing axis search distance multiplier. Computed by this value times the axis max travel.
#define HOMING_AXIS_SEARCH_SCALAR 1.5 // Must be > 1 to ensure limit switch will be engaged. #define HOMING_AXIS_SEARCH_SCALAR 1.5 // Must be > 1 to ensure limit switch will be engaged.
@ -41,11 +30,11 @@ void limits_init()
{ {
LIMIT_DDR &= ~(LIMIT_MASK); // Set as input pins LIMIT_DDR &= ~(LIMIT_MASK); // Set as input pins
if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { #ifdef DISABLE_LIMIT_PIN_PULL_UP
LIMIT_PORT &= ~(LIMIT_MASK); // Normal low operation. Requires external pull-down. LIMIT_PORT &= ~(LIMIT_MASK); // Normal low operation. Requires external pull-down.
} else { #else
LIMIT_PORT |= (LIMIT_MASK); // Enable internal pull-up resistors. Normal high operation. LIMIT_PORT |= (LIMIT_MASK); // Enable internal pull-up resistors. Normal high operation.
} #endif
if (bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE)) { if (bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE)) {
LIMIT_PCMSK |= LIMIT_MASK; // Enable specific pins of the Pin Change Interrupt LIMIT_PCMSK |= LIMIT_MASK; // Enable specific pins of the Pin Change Interrupt
@ -89,9 +78,19 @@ void limits_disable()
// locked out until a homing cycle or a kill lock command. Allows the user to disable the hard // locked out until a homing cycle or a kill lock command. Allows the user to disable the hard
// limit setting if their limits are constantly triggering after a reset and move their axes. // limit setting if their limits are constantly triggering after a reset and move their axes.
if (sys.state != STATE_ALARM) { if (sys.state != STATE_ALARM) {
if (bit_isfalse(sys.execute,EXEC_ALARM)) { if (!(sys.rt_exec_alarm)) {
mc_reset(); // Initiate system kill. #ifdef HARD_LIMIT_FORCE_STATE_CHECK
bit_true_atomic(sys.execute, (EXEC_ALARM | EXEC_CRIT_EVENT)); // Indicate hard limit critical event uint8_t bits = (LIMIT_PIN & LIMIT_MASK);
// Check limit pin state.
if (bit_isfalse(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { bits ^= LIMIT_MASK; }
if (bits) {
mc_reset(); // Initiate system kill.
bit_true_atomic(sys.rt_exec_alarm, (EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate hard limit critical event
}
#else
mc_reset(); // Initiate system kill.
bit_true_atomic(sys.rt_exec_alarm, (EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate hard limit critical event
#endif
} }
} }
} }
@ -102,13 +101,13 @@ void limits_disable()
{ {
WDTCSR &= ~(1<<WDIE); // Disable watchdog timer. WDTCSR &= ~(1<<WDIE); // Disable watchdog timer.
if (sys.state != STATE_ALARM) { // Ignore if already in alarm state. if (sys.state != STATE_ALARM) { // Ignore if already in alarm state.
if (bit_isfalse(sys.execute,EXEC_ALARM)) { if (!(sys.rt_exec_alarm)) {
uint8_t bits = LIMIT_PIN; uint8_t bits = (LIMIT_PIN & LIMIT_MASK);
// Check limit pin state. // Check limit pin state.
if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { bits ^= LIMIT_MASK; } if (bit_isfalse(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { bits ^= LIMIT_MASK; }
if (bits & LIMIT_MASK) { if (bits) {
mc_reset(); // Initiate system kill. mc_reset(); // Initiate system kill.
bit_true_atomic(sys.execute, (EXEC_ALARM | EXEC_CRIT_EVENT)); // Indicate hard limit critical event bit_true_atomic(sys.rt_exec_alarm, (EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate hard limit critical event
} }
} }
} }
@ -121,7 +120,8 @@ void limits_disable()
// the trigger point of the limit switches. The rapid stops are handled by a system level axis lock // the trigger point of the limit switches. The rapid stops are handled by a system level axis lock
// mask, which prevents the stepper algorithm from executing step pulses. Homing motions typically // mask, which prevents the stepper algorithm from executing step pulses. Homing motions typically
// circumvent the processes for executing motions in normal operation. // circumvent the processes for executing motions in normal operation.
// NOTE: Only the abort runtime command can interrupt this process. // NOTE: Only the abort realtime command can interrupt this process.
// TODO: Move limit pin-specific calls to a general function for portability.
void limits_go_home(uint8_t cycle_mask) void limits_go_home(uint8_t cycle_mask)
{ {
if (sys.abort) { return; } // Block if system reset has been issued. if (sys.abort) { return; } // Block if system reset has been issued.
@ -134,19 +134,26 @@ void limits_go_home(uint8_t cycle_mask)
float target[N_AXIS]; float target[N_AXIS];
uint8_t limit_pin[N_AXIS], step_pin[N_AXIS]; uint8_t limit_pin[N_AXIS], step_pin[N_AXIS];
float max_travel = 0.0; float max_travel = 0.0;
for (idx=0; idx<N_AXIS; idx++) { for (idx=0; idx<N_AXIS; idx++) {
// Initialize limit and step pin masks // Initialize limit and step pin masks
limit_pin[idx] = get_limit_pin_mask(idx); limit_pin[idx] = get_limit_pin_mask(idx);
step_pin[idx] = get_step_pin_mask(idx); step_pin[idx] = get_step_pin_mask(idx);
#ifdef COREXY
if ((idx==A_MOTOR)||(idx==B_MOTOR)) { step_pin[idx] = (get_step_pin_mask(X_AXIS)|get_step_pin_mask(Y_AXIS)); }
#endif
if (bit_istrue(cycle_mask,bit(idx))) {
// Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
// NOTE: settings.max_travel[] is stored as a negative value.
max_travel = max(max_travel,(-HOMING_AXIS_SEARCH_SCALAR)*settings.max_travel[idx]);
}
// Determine travel distance to the furthest homing switch based on user max travel settings.
// NOTE: settings.max_travel[] is stored as a negative value.
if (max_travel > settings.max_travel[idx]) { max_travel = settings.max_travel[idx]; }
} }
max_travel *= -HOMING_AXIS_SEARCH_SCALAR; // Ensure homing switches engaged by over-estimating max travel.
plan_reset(); // Reset planner buffer to zero planner current position and to clear previous motions. plan_reset(); // Reset planner buffer to zero planner current position and to clear previous motions.
plan_sync_position(); // Sync planner position to current machine position.
do { do {
// Initialize invert_pin boolean based on approach and invert pin user setting. // Initialize invert_pin boolean based on approach and invert pin user setting.
@ -154,24 +161,25 @@ void limits_go_home(uint8_t cycle_mask)
else { invert_pin = !approach; } else { invert_pin = !approach; }
// Initialize and declare variables needed for homing routine. // Initialize and declare variables needed for homing routine.
uint8_t n_active_axis = 0;
uint8_t axislock = 0; uint8_t axislock = 0;
uint8_t n_active_axis = 0;
system_convert_array_steps_to_mpos(target,sys.position);
for (idx=0; idx<N_AXIS; idx++) { for (idx=0; idx<N_AXIS; idx++) {
// Set target location for active axes and setup computation for homing rate. // Set target location for active axes and setup computation for homing rate.
if (bit_istrue(cycle_mask,bit(idx))) { if (bit_istrue(cycle_mask,bit(idx))) {
n_active_axis++; n_active_axis++;
if (!approach) { target[idx] = -max_travel; } // Set target direction based on cycle mask and homing cycle approach state.
else { target[idx] = max_travel; } if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
} else { if (approach) { target[idx] -= max_travel; }
target[idx] = 0.0; else { target[idx] += max_travel; }
} else {
if (approach) { target[idx] += max_travel; }
else { target[idx] -= max_travel; }
}
// Apply axislock to the step port pins active in this cycle.
axislock |= step_pin[idx];
} }
// Set target direction based on cycle mask
if (bit_istrue(settings.homing_dir_mask,bit(idx))) { target[idx] = -target[idx]; }
// Apply axislock to the step port pins active in this cycle.
if (bit_istrue(cycle_mask,bit(idx))) { axislock |= step_pin[idx]; }
} }
homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate. homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
sys.homing_axis_lock = axislock; sys.homing_axis_lock = axislock;
@ -198,12 +206,19 @@ void limits_go_home(uint8_t cycle_mask)
} }
sys.homing_axis_lock = axislock; sys.homing_axis_lock = axislock;
st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us. st_prep_buffer(); // Check and prep segment buffer. NOTE: Should take no longer than 200us.
// Check only for user reset. No time to run protocol_execute_runtime() in this loop.
if (sys.execute & EXEC_RESET) { protocol_execute_runtime(); return; } // Exit routines: User abort homing and alarm upon safety door or no limit switch found.
// No time to run protocol_execute_realtime() in this loop.
if (sys.rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET | EXEC_CYCLE_STOP)) {
if (sys.rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_CYCLE_STOP)) { mc_reset(); }
protocol_execute_realtime();
return;
}
} while (STEP_MASK & axislock); } while (STEP_MASK & axislock);
st_reset(); // Immediately force kill steppers and reset step segment buffer. st_reset(); // Immediately force kill steppers and reset step segment buffer.
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure homing motion is cleared. plan_reset(); // Reset planner buffer. Zero planner positions. Ensure homing motion is cleared.
plan_sync_position(); // Sync planner position to current machine position
delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate. delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate.
@ -214,50 +229,78 @@ void limits_go_home(uint8_t cycle_mask)
} while (n_cycle-- > 0); } while (n_cycle-- > 0);
// The active cycle axes should now be homed and machine limits have been located. By // The active cycle axes should now be homed and machine limits have been located. By
// default, grbl defines machine space as all negative, as do most CNCs. Since limit switches // default, Grbl defines machine space as all negative, as do most CNCs. Since limit switches
// can be on either side of an axes, check and set axes machine zero appropriately. Also, // can be on either side of an axes, check and set axes machine zero appropriately. Also,
// set up pull-off maneuver from axes limit switches that have been homed. This provides // set up pull-off maneuver from axes limit switches that have been homed. This provides
// some initial clearance off the switches and should also help prevent them from falsely // some initial clearance off the switches and should also help prevent them from falsely
// triggering when hard limits are enabled or when more than one axes shares a limit pin. // triggering when hard limits are enabled or when more than one axes shares a limit pin.
#ifdef COREXY
int32_t off_axis_position = 0;
#endif
int32_t set_axis_position;
// Set machine positions for homed limit switches. Don't update non-homed axes.
for (idx=0; idx<N_AXIS; idx++) { for (idx=0; idx<N_AXIS; idx++) {
// Set up pull off targets and machine positions for limit switches homed in the negative
// direction, rather than the traditional positive. Leave non-homed positions as zero and
// do not move them.
// NOTE: settings.max_travel[] is stored as a negative value. // NOTE: settings.max_travel[] is stored as a negative value.
if (cycle_mask & bit(idx)) { if (cycle_mask & bit(idx)) {
set_axis_position = 0;
#ifdef HOMING_FORCE_SET_ORIGIN #ifndef HOMING_FORCE_SET_ORIGIN
sys.position[idx] = 0; // Set axis homed location as axis origin
target[idx] = settings.homing_pulloff;
if ( bit_isfalse(settings.homing_dir_mask,bit(idx)) ) { target[idx] = -target[idx]; }
#else
if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) { if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) {
target[idx] = settings.homing_pulloff+settings.max_travel[idx]; set_axis_position = lround(settings.max_travel[idx]*settings.steps_per_mm[idx]);
sys.position[idx] = lround(settings.max_travel[idx]*settings.steps_per_mm[idx]);
} else {
target[idx] = -settings.homing_pulloff;
sys.position[idx] = 0;
} }
#endif #endif
} else { // Non-active cycle axis. Set target to not move during pull-off. #ifdef COREXY
target[idx] = (float)sys.position[idx]/settings.steps_per_mm[idx]; if (idx==X_AXIS) {
off_axis_position = (sys.position[B_MOTOR] - sys.position[A_MOTOR])/2;
sys.position[A_MOTOR] = set_axis_position - off_axis_position;
sys.position[B_MOTOR] = set_axis_position + off_axis_position;
} else if (idx==Y_AXIS) {
off_axis_position = (sys.position[A_MOTOR] + sys.position[B_MOTOR])/2;
sys.position[A_MOTOR] = off_axis_position - set_axis_position;
sys.position[B_MOTOR] = off_axis_position + set_axis_position;
} else {
sys.position[idx] = set_axis_position;
}
#else
sys.position[idx] = set_axis_position;
#endif
} }
} }
plan_sync_position(); // Sync planner position to current machine position for pull-off move. plan_sync_position(); // Sync planner position to homed machine position.
#ifdef USE_LINE_NUMBERS // Set pull-off motion target. Seperated from above loop if target is dependent on sys.position.
plan_buffer_line(target, settings.homing_seek_rate, false, HOMING_CYCLE_LINE_NUMBER); // Bypass mc_line(). Directly plan motion. if (settings.homing_pulloff > 0.0) {
#else for (idx=0; idx<N_AXIS; idx++) {
plan_buffer_line(target, settings.homing_seek_rate, false); // Bypass mc_line(). Directly plan motion. if (cycle_mask & bit(idx)) {
#endif #ifdef HOMING_FORCE_SET_ORIGIN
target[idx] = settings.homing_pulloff;
if ( bit_isfalse(settings.homing_dir_mask,bit(idx)) ) { target[idx] = -target[idx]; }
#else
if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) {
target[idx] = settings.homing_pulloff+settings.max_travel[idx];
} else {
target[idx] = -settings.homing_pulloff;
}
#endif
} else {
// Non-active cycle axis. Set target to not move during pull-off.
target[idx] = system_convert_axis_steps_to_mpos(sys.position, idx);
}
}
#ifdef USE_LINE_NUMBERS
plan_buffer_line(target, settings.homing_seek_rate, false, HOMING_CYCLE_LINE_NUMBER); // Bypass mc_line(). Directly plan motion.
#else
plan_buffer_line(target, settings.homing_seek_rate, false); // Bypass mc_line(). Directly plan motion.
#endif
// Initiate pull-off using main motion control routines. // Initiate pull-off using main motion control routines.
// TODO : Clean up state routines so that this motion still shows homing state. // TODO : Clean up state routines so that this motion still shows homing state.
sys.state = STATE_QUEUED; sys.state = STATE_IDLE;
bit_true_atomic(sys.execute, EXEC_CYCLE_START); bit_true_atomic(sys.rt_exec_state, EXEC_CYCLE_START);
protocol_execute_runtime(); protocol_execute_realtime();
protocol_buffer_synchronize(); // Complete pull-off motion. protocol_buffer_synchronize(); // Complete pull-off motion.
}
// Set system state to homing before returning. // Set system state to homing before returning.
sys.state = STATE_HOMING; sys.state = STATE_HOMING;
@ -290,16 +333,16 @@ void limits_soft_check(float *target)
// workspace volume so just come to a controlled stop so position is not lost. When complete // workspace volume so just come to a controlled stop so position is not lost. When complete
// enter alarm mode. // enter alarm mode.
if (sys.state == STATE_CYCLE) { if (sys.state == STATE_CYCLE) {
bit_true_atomic(sys.execute, EXEC_FEED_HOLD); bit_true_atomic(sys.rt_exec_state, EXEC_FEED_HOLD);
do { do {
protocol_execute_runtime(); protocol_execute_realtime();
if (sys.abort) { return; } if (sys.abort) { return; }
} while ( sys.state != STATE_IDLE || sys.state != STATE_QUEUED); } while ( sys.state != STATE_IDLE );
} }
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
bit_true_atomic(sys.execute, (EXEC_ALARM | EXEC_CRIT_EVENT)); // Indicate soft limit critical event bit_true_atomic(sys.rt_exec_alarm, (EXEC_ALARM_SOFT_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate soft limit critical event
protocol_execute_runtime(); // Execute to enter critical event loop and system abort protocol_execute_realtime(); // Execute to enter critical event loop and system abort
return; return;
} }
} }

View File

@ -1,8 +1,9 @@
/* /*
limits.h - code pertaining to limit-switches and performing the homing cycle limits.h - code pertaining to limit-switches and performing the homing cycle
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,11 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
*/
#ifndef limits_h #ifndef limits_h
#define limits_h #define limits_h

View File

@ -1,8 +1,9 @@
/* /*
main.c - An embedded CNC Controller with rs274/ngc (g-code) support main.c - An embedded CNC Controller with rs274/ngc (g-code) support
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,26 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "serial.h"
#include "settings.h"
#include "protocol.h"
#include "gcode.h"
#include "planner.h"
#include "stepper.h"
#include "spindle_control.h"
#include "coolant_control.h"
#include "motion_control.h"
#include "limits.h"
#include "probe.h"
#include "report.h"
// Declare system global variable structure // Declare system global variable structure
@ -47,7 +30,7 @@ int main(void)
{ {
// Initialize system upon power-up. // Initialize system upon power-up.
serial_init(); // Setup serial baud rate and interrupts serial_init(); // Setup serial baud rate and interrupts
settings_init(); // Load grbl settings from EEPROM settings_init(); // Load Grbl settings from EEPROM
stepper_init(); // Configure stepper pins and interrupt timers stepper_init(); // Configure stepper pins and interrupt timers
system_init(); // Configure pinout pins and pin-change interrupt system_init(); // Configure pinout pins and pin-change interrupt
@ -66,6 +49,11 @@ int main(void)
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { sys.state = STATE_ALARM; } if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { sys.state = STATE_ALARM; }
#endif #endif
// Force Grbl into an ALARM state upon a power-cycle or hard reset.
#ifdef FORCE_INITIALIZATION_ALARM
sys.state = STATE_ALARM;
#endif
// Grbl initialization loop upon power-up or a system abort. For the latter, all processes // Grbl initialization loop upon power-up or a system abort. For the latter, all processes
// will return to this loop to be cleanly re-initialized. // will return to this loop to be cleanly re-initialized.
for(;;) { for(;;) {
@ -89,9 +77,9 @@ int main(void)
// Reset system variables. // Reset system variables.
sys.abort = false; sys.abort = false;
sys.execute = 0; sys.rt_exec_state = 0;
if (bit_istrue(settings.flags,BITFLAG_AUTO_START)) { sys.auto_start = true; } sys.rt_exec_alarm = 0;
else { sys.auto_start = false; } sys.suspend = false;
// Start Grbl main loop. Processes program inputs and executes them. // Start Grbl main loop. Processes program inputs and executes them.
protocol_main_loop(); protocol_main_loop();

View File

@ -1,8 +1,10 @@
/* /*
motion_control.c - high level interface for issuing motion commands motion_control.c - high level interface for issuing motion commands
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,26 +19,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
Copyright (c) 2011 Jens Geisler
*/
#include "system.h" #include "grbl.h"
#include "settings.h"
#include "protocol.h"
#include "gcode.h"
#include "planner.h"
#include "stepper.h"
#include "motion_control.h"
#include "spindle_control.h"
#include "coolant_control.h"
#include "limits.h"
#include "probe.h"
#include "report.h"
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second // Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
@ -76,26 +60,23 @@
// If the buffer is full: good! That means we are well ahead of the robot. // If the buffer is full: good! That means we are well ahead of the robot.
// Remain in this loop until there is room in the buffer. // Remain in this loop until there is room in the buffer.
do { do {
protocol_execute_runtime(); // Check for any run-time commands protocol_execute_realtime(); // Check for any run-time commands
if (sys.abort) { return; } // Bail, if system abort. if (sys.abort) { return; } // Bail, if system abort.
if ( plan_check_full_buffer() ) { protocol_auto_cycle_start(); } // Auto-cycle start when buffer is full. if ( plan_check_full_buffer() ) { protocol_auto_cycle_start(); } // Auto-cycle start when buffer is full.
else { break; } else { break; }
} while (1); } while (1);
// Plan and queue motion into planner buffer
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
plan_buffer_line(target, feed_rate, invert_feed_rate, line_number); plan_buffer_line(target, feed_rate, invert_feed_rate, line_number);
#else #else
plan_buffer_line(target, feed_rate, invert_feed_rate); plan_buffer_line(target, feed_rate, invert_feed_rate);
#endif #endif
// If idle, indicate to the system there is now a planned block in the buffer ready to cycle
// start. Otherwise ignore and continue on.
if (!sys.state) { sys.state = STATE_QUEUED; }
} }
// Execute an arc in offset mode format. position == current xyz, target == target xyz, // Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is // offset == offset from current xyz, axis_X defines circle plane in tool space, axis_linear is
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used // the direction of helical travel, radius == circle radius, isclockwise boolean. Used
// for vector transformation direction. // for vector transformation direction.
// The arc is approximated by generating a huge number of tiny, linear segments. The chordal tolerance // The arc is approximated by generating a huge number of tiny, linear segments. The chordal tolerance
@ -103,10 +84,10 @@
// distance from segment to the circle when the end points both lie on the circle. // distance from segment to the circle when the end points both lie on the circle.
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate, void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, int32_t line_number) uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc, int32_t line_number)
#else #else
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate, void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear) uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc)
#endif #endif
{ {
float center_axis0 = position[axis_0] + offset[axis_0]; float center_axis0 = position[axis_0] + offset[axis_0];
@ -118,7 +99,7 @@
// CCW angle between position and target from circle center. Only one atan2() trig computation required. // CCW angle between position and target from circle center. Only one atan2() trig computation required.
float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1); float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1);
if (gc_state.modal.motion == MOTION_MODE_CW_ARC) { // Correct atan2 output per direction if (is_clockwise_arc) { // Correct atan2 output per direction
if (angular_travel >= 0) { angular_travel -= 2*M_PI; } if (angular_travel >= 0) { angular_travel -= 2*M_PI; }
} else { } else {
if (angular_travel <= 0) { angular_travel += 2*M_PI; } if (angular_travel <= 0) { angular_travel += 2*M_PI; }
@ -227,8 +208,8 @@ void mc_dwell(float seconds)
protocol_buffer_synchronize(); protocol_buffer_synchronize();
delay_ms(floor(1000*seconds-i*DWELL_TIME_STEP)); // Delay millisecond remainder. delay_ms(floor(1000*seconds-i*DWELL_TIME_STEP)); // Delay millisecond remainder.
while (i-- > 0) { while (i-- > 0) {
// NOTE: Check and execute runtime commands during dwell every <= DWELL_TIME_STEP milliseconds. // NOTE: Check and execute realtime commands during dwell every <= DWELL_TIME_STEP milliseconds.
protocol_execute_runtime(); protocol_execute_realtime();
if (sys.abort) { return; } if (sys.abort) { return; }
_delay_ms(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment _delay_ms(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment
} }
@ -240,7 +221,19 @@ void mc_dwell(float seconds)
// executing the homing cycle. This prevents incorrect buffered plans after homing. // executing the homing cycle. This prevents incorrect buffered plans after homing.
void mc_homing_cycle() void mc_homing_cycle()
{ {
sys.state = STATE_HOMING; // Set system state variable // 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.
// TODO: Move the pin-specific LIMIT_PIN call to limits.c as a function.
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
uint8_t limit_state = (LIMIT_PIN & LIMIT_MASK);
if (bit_isfalse(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { limit_state ^= LIMIT_MASK; }
if (limit_state) {
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
bit_true_atomic(sys.rt_exec_alarm, (EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT));
return;
}
#endif
limits_disable(); // Disable hard limits pin change register for cycle duration limits_disable(); // Disable hard limits pin change register for cycle duration
// ------------------------------------------------------------------------------------- // -------------------------------------------------------------------------------------
@ -255,7 +248,7 @@ void mc_homing_cycle()
limits_go_home(HOMING_CYCLE_2); // Homing cycle 2 limits_go_home(HOMING_CYCLE_2); // Homing cycle 2
#endif #endif
protocol_execute_runtime(); // Check for reset and set system abort. protocol_execute_realtime(); // Check for reset and set system abort.
if (sys.abort) { return; } // Did not complete. Alarm state set by mc_alarm. if (sys.abort) { return; } // Did not complete. Alarm state set by mc_alarm.
// Homing cycle complete! Setup system for normal operation. // Homing cycle complete! Setup system for normal operation.
@ -264,10 +257,6 @@ void mc_homing_cycle()
// Gcode parser position was circumvented by the limits_go_home() routine, so sync position now. // Gcode parser position was circumvented by the limits_go_home() routine, so sync position now.
gc_sync_position(); gc_sync_position();
// Set idle state after homing completes and before returning to main program.
sys.state = STATE_IDLE;
st_go_idle(); // Set idle state after homing completes
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle. // If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
limits_init(); limits_init();
} }
@ -276,9 +265,11 @@ void mc_homing_cycle()
// Perform tool length probe cycle. Requires probe switch. // Perform tool length probe cycle. Requires probe switch.
// NOTE: Upon probe failure, the program will be stopped and placed into ALARM state. // NOTE: Upon probe failure, the program will be stopped and placed into ALARM state.
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, int32_t line_number) void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
uint8_t is_no_error, int32_t line_number)
#else #else
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate) void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
uint8_t is_no_error)
#endif #endif
{ {
// TODO: Need to update this cycle so it obeys a non-auto cycle start. // TODO: Need to update this cycle so it obeys a non-auto cycle start.
@ -286,12 +277,16 @@ void mc_homing_cycle()
// Finish all queued commands and empty planner buffer before starting probe cycle. // Finish all queued commands and empty planner buffer before starting probe cycle.
protocol_buffer_synchronize(); protocol_buffer_synchronize();
uint8_t auto_start_state = sys.auto_start; // Store run state
// Initialize probing control variables
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
probe_configure_invert_mask(is_probe_away);
// After syncing, check if probe is already triggered. If so, halt and issue alarm. // After syncing, check if probe is already triggered. If so, halt and issue alarm.
if (probe_get_state()) { // NOTE: This probe initialization error applies to all probing cycles.
bit_true_atomic(sys.execute, EXEC_CRIT_EVENT); if ( probe_get_state() ) { // Check probe pin state.
protocol_execute_runtime(); bit_true_atomic(sys.rt_exec_alarm, EXEC_ALARM_PROBE_FAIL);
protocol_execute_realtime();
} }
if (sys.abort) { return; } // Return if system reset has been issued. if (sys.abort) { return; } // Return if system reset has been issued.
@ -302,19 +297,27 @@ void mc_homing_cycle()
mc_line(target, feed_rate, invert_feed_rate); mc_line(target, feed_rate, invert_feed_rate);
#endif #endif
// Activate the probing monitor in the stepper module. // Activate the probing state monitor in the stepper module.
sys.probe_state = PROBE_ACTIVE; sys.probe_state = PROBE_ACTIVE;
// Perform probing cycle. Wait here until probe is triggered or motion completes. // Perform probing cycle. Wait here until probe is triggered or motion completes.
bit_true_atomic(sys.execute, EXEC_CYCLE_START); bit_true_atomic(sys.rt_exec_state, EXEC_CYCLE_START);
do { do {
protocol_execute_runtime(); protocol_execute_realtime();
if (sys.abort) { return; } // Check for system abort if (sys.abort) { return; } // Check for system abort
} while ((sys.state != STATE_IDLE) && (sys.state != STATE_QUEUED)); } while (sys.state != STATE_IDLE);
// Probing motion complete. If the probe has not been triggered, error out. // Probing cycle complete!
if (sys.probe_state == PROBE_ACTIVE) { bit_true_atomic(sys.execute, EXEC_CRIT_EVENT); }
protocol_execute_runtime(); // Check and execute run-time commands // Set state variables and error out, if the probe failed and cycle with error is enabled.
if (sys.probe_state == PROBE_ACTIVE) {
if (is_no_error) { memcpy(sys.probe_position, sys.position, sizeof(float)*N_AXIS); }
else { bit_true_atomic(sys.rt_exec_alarm, EXEC_ALARM_PROBE_FAIL); }
} else {
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
}
sys.probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
protocol_execute_realtime(); // Check and execute run-time commands
if (sys.abort) { return; } // Check for system abort if (sys.abort) { return; } // Check for system abort
// Reset the stepper and planner buffers to remove the remainder of the probe motion. // Reset the stepper and planner buffers to remove the remainder of the probe motion.
@ -322,25 +325,9 @@ void mc_homing_cycle()
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared. plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
plan_sync_position(); // Sync planner position to current machine position. plan_sync_position(); // Sync planner position to current machine position.
// Pull-off triggered probe to the trigger location since we had to decelerate a little beyond // TODO: Update the g-code parser code to not require this target calculation but uses a gc_sync_position() call.
// it to stop the machine in a controlled manner. // NOTE: The target[] variable updated here will be sent back and synced with the g-code parser.
uint8_t idx; system_convert_array_steps_to_mpos(target, sys.position);
for(idx=0; idx<N_AXIS; idx++){
// NOTE: The target[] variable updated here will be sent back and synced with the g-code parser.
target[idx] = (float)sys.probe_position[idx]/settings.steps_per_mm[idx];
}
#ifdef USE_LINE_NUMBERS
mc_line(target, feed_rate, invert_feed_rate, line_number);
#else
mc_line(target, feed_rate, invert_feed_rate);
#endif
// Execute pull-off motion and wait until it completes.
bit_true_atomic(sys.execute, EXEC_CYCLE_START);
protocol_buffer_synchronize();
if (sys.abort) { return; } // Return if system reset has been issued.
sys.auto_start = auto_start_state; // Restore run state before returning
#ifdef MESSAGE_PROBE_COORDINATES #ifdef MESSAGE_PROBE_COORDINATES
// All done! Output the probe position as message. // All done! Output the probe position as message.
@ -349,27 +336,28 @@ void mc_homing_cycle()
} }
// Method to ready the system to reset by setting the runtime reset command and killing any // Method to ready the system to reset by setting the realtime reset command and killing any
// active processes in the system. This also checks if a system reset is issued while Grbl // active processes in the system. This also checks if a system reset is issued while Grbl
// is in a motion state. If so, kills the steppers and sets the system alarm to flag position // is in a motion state. If so, kills the steppers and sets the system alarm to flag position
// lost, since there was an abrupt uncontrolled deceleration. Called at an interrupt level by // lost, since there was an abrupt uncontrolled deceleration. Called at an interrupt level by
// runtime abort command and hard limits. So, keep to a minimum. // realtime abort command and hard limits. So, keep to a minimum.
void mc_reset() void mc_reset()
{ {
// Only this function can set the system reset. Helps prevent multiple kill calls. // Only this function can set the system reset. Helps prevent multiple kill calls.
if (bit_isfalse(sys.execute, EXEC_RESET)) { if (bit_isfalse(sys.rt_exec_state, EXEC_RESET)) {
bit_true_atomic(sys.execute, EXEC_RESET); bit_true_atomic(sys.rt_exec_state, EXEC_RESET);
// Kill spindle and coolant. // Kill spindle and coolant.
spindle_stop(); spindle_stop();
coolant_stop(); coolant_stop();
// Kill steppers only if in any motion state, i.e. cycle, feed hold, homing, or jogging // 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 // NOTE: If steppers are kept enabled via the step idle delay setting, this also keeps
// the steppers enabled by avoiding the go_idle call altogether, unless the motion state is // the steppers enabled by avoiding the go_idle call altogether, unless the motion state is
// violated, by which, all bets are off. // violated, by which, all bets are off.
if (sys.state & (STATE_CYCLE | STATE_HOLD | STATE_HOMING)) { if ((sys.state & (STATE_CYCLE | STATE_HOMING)) || (sys.suspend == SUSPEND_ENABLE_HOLD)) {
bit_true_atomic(sys.execute, EXEC_ALARM); // Flag main program to execute alarm state. if (sys.state == STATE_HOMING) { bit_true_atomic(sys.rt_exec_alarm, EXEC_ALARM_HOMING_FAIL); }
else { bit_true_atomic(sys.rt_exec_alarm, EXEC_ALARM_ABORT_CYCLE); }
st_go_idle(); // Force kill steppers. Position has likely been lost. st_go_idle(); // Force kill steppers. Position has likely been lost.
} }
} }

View File

@ -1,8 +1,9 @@
/* /*
motion_control.h - high level interface for issuing motion commands motion_control.h - high level interface for issuing motion commands
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,16 +18,11 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef motion_control_h #ifndef motion_control_h
#define motion_control_h #define motion_control_h
#define HOMING_CYCLE_LINE_NUMBER -1 #define HOMING_CYCLE_LINE_NUMBER -1
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second // Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
@ -40,14 +36,14 @@ void mc_line(float *target, float feed_rate, uint8_t invert_feed_rate);
// Execute an arc in offset mode format. position == current xyz, target == target xyz, // Execute an arc in offset mode format. position == current xyz, target == target xyz,
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is // offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used // the direction of helical travel, radius == circle radius, is_clockwise_arc boolean. Used
// for vector transformation direction. // for vector transformation direction.
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate, void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, int32_t line_number); uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc, int32_t line_number);
#else #else
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate, void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear); uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc);
#endif #endif
// Dwell for a specific number of seconds // Dwell for a specific number of seconds
@ -58,9 +54,11 @@ void mc_homing_cycle();
// Perform tool length probe cycle. Requires probe switch. // Perform tool length probe cycle. Requires probe switch.
#ifdef USE_LINE_NUMBERS #ifdef USE_LINE_NUMBERS
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, int32_t line_number); void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
uint8_t is_no_error, int32_t line_number);
#else #else
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate); void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
uint8_t is_no_error);
#endif #endif
// Performs system reset. If in motion state, kills all motion and sets system alarm. // Performs system reset. If in motion state, kills all motion and sets system alarm.

View File

@ -1,8 +1,9 @@
/* /*
nuts_bolts.c - Shared functions nuts_bolts.c - Shared functions
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,15 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "print.h"
#define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float) #define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float)

View File

@ -1,8 +1,9 @@
/* /*
nuts_bolts.h - Header file for shared definitions, variables, and functions nuts_bolts.h - Header file for shared definitions, variables, and functions
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef nuts_bolts_h #ifndef nuts_bolts_h
#define nuts_bolts_h #define nuts_bolts_h
@ -30,15 +25,23 @@
#define false 0 #define false 0
#define true 1 #define true 1
// Axis array index values. Must start with 0 and be continuous.
#define N_AXIS 3 // Number of axes #define N_AXIS 3 // Number of axes
#define X_AXIS 0 // Axis indexing value. Must start with 0 and be continuous. #define X_AXIS 0 // Axis indexing value.
#define Y_AXIS 1 #define Y_AXIS 1
#define Z_AXIS 2 #define Z_AXIS 2
// #define A_AXIS 3 // #define A_AXIS 3
// CoreXY motor assignments. DO NOT ALTER.
// NOTE: If the A and B motor axis bindings are changed, this effects the CoreXY equations.
#ifdef COREXY
#define A_MOTOR X_AXIS // Must be X_AXIS
#define B_MOTOR Y_AXIS // Must be Y_AXIS
#endif
// Conversions
#define MM_PER_INCH (25.40) #define MM_PER_INCH (25.40)
#define INCH_PER_MM (0.0393701) #define INCH_PER_MM (0.0393701)
#define TICKS_PER_MICROSECOND (F_CPU/1000000) #define TICKS_PER_MICROSECOND (F_CPU/1000000)
// Useful macros // Useful macros

View File

@ -1,8 +1,10 @@
/* /*
planner.c - buffers movement commands and manages the acceleration profile plan planner.c - buffers movement commands and manages the acceleration profile plan
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011 Jens Geisler
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,20 +19,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
Copyright (c) 2011 Jens Geisler
*/
#include "system.h"
#include "planner.h"
#include "protocol.h"
#include "stepper.h"
#include "settings.h"
#include "grbl.h"
#define SOME_LARGE_VALUE 1.0E+38 // Used by rapids and acceleration maximization calculations. Just needs #define SOME_LARGE_VALUE 1.0E+38 // Used by rapids and acceleration maximization calculations. Just needs
// to be larger than any feasible (mm/min)^2 or mm/sec^2 value. // to be larger than any feasible (mm/min)^2 or mm/sec^2 value.
@ -284,17 +274,36 @@ uint8_t plan_check_full_buffer()
int32_t target_steps[N_AXIS]; int32_t target_steps[N_AXIS];
float unit_vec[N_AXIS], delta_mm; float unit_vec[N_AXIS], delta_mm;
uint8_t idx; uint8_t idx;
#ifdef COREXY
target_steps[A_MOTOR] = lround(target[A_MOTOR]*settings.steps_per_mm[A_MOTOR]);
target_steps[B_MOTOR] = lround(target[B_MOTOR]*settings.steps_per_mm[B_MOTOR]);
block->steps[A_MOTOR] = labs((target_steps[X_AXIS]-pl.position[X_AXIS]) - (target_steps[Y_AXIS]-pl.position[Y_AXIS]));
block->steps[B_MOTOR] = labs((target_steps[X_AXIS]-pl.position[X_AXIS]) + (target_steps[Y_AXIS]-pl.position[Y_AXIS]));
#endif
for (idx=0; idx<N_AXIS; idx++) { for (idx=0; idx<N_AXIS; idx++) {
// Calculate target position in absolute steps. This conversion should be consistent throughout. // Calculate target position in absolute steps, number of steps for each axis, and determine max step events.
target_steps[idx] = lround(target[idx]*settings.steps_per_mm[idx]); // Also, compute individual axes distance for move and prep unit vector calculations.
// Number of steps for each axis and determine max step events
block->steps[idx] = labs(target_steps[idx]-pl.position[idx]);
block->step_event_count = max(block->step_event_count, block->steps[idx]);
// Compute individual axes distance for move and prep unit vector calculations.
// NOTE: Computes true distance from converted step values. // NOTE: Computes true distance from converted step values.
delta_mm = (target_steps[idx] - pl.position[idx])/settings.steps_per_mm[idx]; #ifdef COREXY
if ( !(idx == A_MOTOR) && !(idx == B_MOTOR) ) {
target_steps[idx] = lround(target[idx]*settings.steps_per_mm[idx]);
block->steps[idx] = labs(target_steps[idx]-pl.position[idx]);
}
block->step_event_count = max(block->step_event_count, block->steps[idx]);
if (idx == A_MOTOR) {
delta_mm = ((target_steps[X_AXIS]-pl.position[X_AXIS]) - (target_steps[Y_AXIS]-pl.position[Y_AXIS]))/settings.steps_per_mm[idx];
} else if (idx == B_MOTOR) {
delta_mm = ((target_steps[X_AXIS]-pl.position[X_AXIS]) + (target_steps[Y_AXIS]-pl.position[Y_AXIS]))/settings.steps_per_mm[idx];
} else {
delta_mm = (target_steps[idx] - pl.position[idx])/settings.steps_per_mm[idx];
}
#else
target_steps[idx] = lround(target[idx]*settings.steps_per_mm[idx]);
block->steps[idx] = labs(target_steps[idx]-pl.position[idx]);
block->step_event_count = max(block->step_event_count, block->steps[idx]);
delta_mm = (target_steps[idx] - pl.position[idx])/settings.steps_per_mm[idx];
#endif
unit_vec[idx] = delta_mm; // Store unit vector numerator. Denominator computed later. unit_vec[idx] = delta_mm; // Store unit vector numerator. Denominator computed later.
// Set direction bits. Bit enabled always means direction is negative. // Set direction bits. Bit enabled always means direction is negative.
@ -352,7 +361,7 @@ uint8_t plan_check_full_buffer()
colinear with the circle center. The circular segment joining the two paths represents the colinear with the circle center. The circular segment joining the two paths represents the
path of centripetal acceleration. Solve for max velocity based on max acceleration about the path of centripetal acceleration. Solve for max velocity based on max acceleration about the
radius of the circle, defined indirectly by junction deviation. This may be also viewed as radius of the circle, defined indirectly by junction deviation. This may be also viewed as
path width or max_jerk in the previous grbl version. This approach does not actually deviate path width or max_jerk in the previous Grbl version. This approach does not actually deviate
from path, but used as a robust way to compute cornering speeds, as it takes into account the from path, but used as a robust way to compute cornering speeds, as it takes into account the
nonlinearities of both the junction angle and junction velocity. nonlinearities of both the junction angle and junction velocity.
@ -369,12 +378,19 @@ uint8_t plan_check_full_buffer()
change the overall maximum entry speed conditions of all blocks. change the overall maximum entry speed conditions of all blocks.
*/ */
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta). // NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
float sin_theta_d2 = sqrt(0.5*(1.0-junction_cos_theta)); // Trig half angle identity. Always positive. if (junction_cos_theta > 0.99) {
// For a 0 degree acute junction, just set minimum junction speed.
block->max_junction_speed_sqr = MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED;
} else {
junction_cos_theta = max(junction_cos_theta,-0.99); // Check for numerical round-off to avoid divide by zero.
float sin_theta_d2 = sqrt(0.5*(1.0-junction_cos_theta)); // Trig half angle identity. Always positive.
// TODO: Technically, the acceleration used in calculation needs to be limited by the minimum of the // TODO: Technically, the acceleration used in calculation needs to be limited by the minimum of the
// two junctions. However, this shouldn't be a significant problem except in extreme circumstances. // two junctions. However, this shouldn't be a significant problem except in extreme circumstances.
block->max_junction_speed_sqr = max( MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED, block->max_junction_speed_sqr = max( MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED,
(block->acceleration * settings.junction_deviation * sin_theta_d2)/(1.0-sin_theta_d2) ); (block->acceleration * settings.junction_deviation * sin_theta_d2)/(1.0-sin_theta_d2) );
}
} }
// Store block nominal speed // Store block nominal speed
@ -403,9 +419,21 @@ uint8_t plan_check_full_buffer()
// Reset the planner position vectors. Called by the system abort/initialization routine. // Reset the planner position vectors. Called by the system abort/initialization routine.
void plan_sync_position() void plan_sync_position()
{ {
// TODO: For motor configurations not in the same coordinate frame as the machine position,
// this function needs to be updated to accomodate the difference.
uint8_t idx; uint8_t idx;
for (idx=0; idx<N_AXIS; idx++) { for (idx=0; idx<N_AXIS; idx++) {
pl.position[idx] = sys.position[idx]; #ifdef COREXY
if (idx==A_MOTOR) {
pl.position[idx] = (sys.position[A_MOTOR] + sys.position[B_MOTOR])/2;
} else if (idx==B_MOTOR) {
pl.position[idx] = (sys.position[A_MOTOR] - sys.position[B_MOTOR])/2;
} else {
pl.position[idx] = sys.position[idx];
}
#else
pl.position[idx] = sys.position[idx];
#endif
} }
} }

View File

@ -1,8 +1,9 @@
/* /*
planner.h - buffers movement commands and manages the acceleration profile plan planner.h - buffers movement commands and manages the acceleration profile plan
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef planner_h #ifndef planner_h
#define planner_h #define planner_h

View File

@ -1,8 +1,9 @@
/* /*
print.c - Functions for formatting output strings print.c - Functions for formatting output strings
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,16 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "serial.h"
#include "settings.h"
void printString(const char *s) void printString(const char *s)
@ -102,7 +95,7 @@ void print_uint8_base10(uint8_t n)
} }
void print_uint32_base10(unsigned long n) void print_uint32_base10(uint32_t n)
{ {
if (n == 0) { if (n == 0) {
serial_write('0'); serial_write('0');

View File

@ -1,8 +1,9 @@
/* /*
print.h - Functions for formatting output strings print.h - Functions for formatting output strings
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef print_h #ifndef print_h
#define print_h #define print_h

View File

@ -1,8 +1,8 @@
/* /*
probe.c - code pertaining to probing methods probe.c - code pertaining to probing methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2014 Sungeun K. Jeon Copyright (c) 2014-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -18,11 +18,10 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
#include "system.h" #include "grbl.h"
#include "settings.h"
#include "probe.h"
// Inverts the probe pin state depending on user settings.
// Inverts the probe pin state depending on user settings and probing cycle mode.
uint8_t probe_invert_mask; uint8_t probe_invert_mask;
@ -30,13 +29,23 @@ uint8_t probe_invert_mask;
void probe_init() void probe_init()
{ {
PROBE_DDR &= ~(PROBE_MASK); // Configure as input pins PROBE_DDR &= ~(PROBE_MASK); // Configure as input pins
if (bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN)) { #ifdef DISABLE_PROBE_PIN_PULL_UP
PROBE_PORT &= ~(PROBE_MASK); // Normal low operation. Requires external pull-down. PROBE_PORT &= ~(PROBE_MASK); // Normal low operation. Requires external pull-down.
probe_invert_mask = 0; #else
} else {
PROBE_PORT |= PROBE_MASK; // Enable internal pull-up resistors. Normal high operation. PROBE_PORT |= PROBE_MASK; // Enable internal pull-up resistors. Normal high operation.
probe_invert_mask = PROBE_MASK; #endif
} // probe_configure_invert_mask(false); // Initialize invert mask. Not required. Updated when in-use.
}
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
// appropriately set the pin logic according to setting for normal-high/normal-low operation
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
void probe_configure_invert_mask(uint8_t is_probe_away)
{
probe_invert_mask = 0; // Initialize as zero.
if (bit_isfalse(settings.flags,BITFLAG_INVERT_PROBE_PIN)) { probe_invert_mask ^= PROBE_MASK; }
if (is_probe_away) { probe_invert_mask ^= PROBE_MASK; }
} }
@ -53,7 +62,7 @@ void probe_state_monitor()
if (probe_get_state()) { if (probe_get_state()) {
sys.probe_state = PROBE_OFF; sys.probe_state = PROBE_OFF;
memcpy(sys.probe_position, sys.position, sizeof(float)*N_AXIS); memcpy(sys.probe_position, sys.position, sizeof(float)*N_AXIS);
bit_true(sys.execute, EXEC_FEED_HOLD); bit_true(sys.rt_exec_state, EXEC_MOTION_CANCEL);
} }
} }
} }

View File

@ -1,8 +1,8 @@
/* /*
probe.h - code pertaining to probing methods probe.h - code pertaining to probing methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2014 Sungeun K. Jeon Copyright (c) 2014-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -22,14 +22,18 @@
#define probe_h #define probe_h
// Values that define the probing state machine. // Values that define the probing state machine.
#define PROBE_OFF 0 // No probing. (Must be zero.) #define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.)
#define PROBE_ACTIVE 1 // Actively watching the input pin. #define PROBE_ACTIVE 1 // Actively watching the input pin.
// Probe pin initialization routine. // Probe pin initialization routine.
void probe_init(); void probe_init();
// Returns probe pin state. // Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
// appropriately set the pin logic according to setting for normal-high/normal-low operation
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
void probe_configure_invert_mask(uint8_t is_probe_away);
// Returns probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
uint8_t probe_get_state(); uint8_t probe_get_state();
// Monitors probe pin state and records the system position when detected. Called by the // Monitors probe pin state and records the system position when detected. Called by the

389
grbl/protocol.c Normal file
View File

@ -0,0 +1,389 @@
/*
protocol.c - controls Grbl execution protocol and procedures
Part of Grbl
Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "grbl.h"
static char line[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
// Directs and executes one line of formatted input from protocol_process. While mostly
// incoming streaming g-code blocks, this also directs and executes Grbl internal commands,
// such as settings, initiating the homing cycle, and toggling switch states.
static void protocol_execute_line(char *line)
{
protocol_execute_realtime(); // Runtime command check point.
if (sys.abort) { return; } // Bail to calling function upon system abort
if (line[0] == 0) {
// Empty or comment line. Send status message for syncing purposes.
report_status_message(STATUS_OK);
} else if (line[0] == '$') {
// Grbl '$' system command
report_status_message(system_execute_line(line));
} else if (sys.state == STATE_ALARM) {
// Everything else is gcode. Block if in alarm mode.
report_status_message(STATUS_ALARM_LOCK);
} else {
// Parse and execute g-code block!
report_status_message(gc_execute_line(line));
}
}
/*
GRBL PRIMARY LOOP:
*/
void protocol_main_loop()
{
// ------------------------------------------------------------
// Complete initialization procedures upon a power-up or reset.
// ------------------------------------------------------------
// Print welcome message
report_init_message();
// Check for and report alarm state after a reset, error, or an initial power up.
if (sys.state == STATE_ALARM) {
report_feedback_message(MESSAGE_ALARM_LOCK);
} else {
// All systems go! But first check for safety door.
if (system_check_safety_door_ajar()) {
bit_true(sys.rt_exec_state, EXEC_SAFETY_DOOR);
protocol_execute_realtime(); // Enter safety door mode. Should return as IDLE state.
} else {
sys.state = STATE_IDLE; // Set system to ready. Clear all state flags.
}
system_execute_startup(line); // Execute startup script.
}
// ---------------------------------------------------------------------------------
// Primary loop! Upon a system abort, this exits back to main() to reset the system.
// ---------------------------------------------------------------------------------
uint8_t iscomment = false;
uint8_t char_counter = 0;
uint8_t c;
for (;;) {
// Process one line of incoming serial data, as the data becomes available. Performs an
// initial filtering by removing spaces and comments and capitalizing all letters.
// NOTE: While comment, spaces, and block delete(if supported) handling should technically
// be done in the g-code parser, doing it here helps compress the incoming data into Grbl's
// line buffer, which is limited in size. The g-code standard actually states a line can't
// exceed 256 characters, but the Arduino Uno does not have the memory space for this.
// With a better processor, it would be very easy to pull this initial parsing out as a
// seperate task to be shared by the g-code parser and Grbl's system commands.
while((c = serial_read()) != SERIAL_NO_DATA) {
if ((c == '\n') || (c == '\r')) { // End of line reached
line[char_counter] = 0; // Set string termination character.
protocol_execute_line(line); // Line is complete. Execute it!
iscomment = false;
char_counter = 0;
} else {
if (iscomment) {
// Throw away all comment characters
if (c == ')') {
// End of comment. Resume line.
iscomment = false;
}
} else {
if (c <= ' ') {
// Throw away whitepace and control characters
} else if (c == '/') {
// Block delete NOT SUPPORTED. Ignore character.
// NOTE: If supported, would simply need to check the system if block delete is enabled.
} else if (c == '(') {
// Enable comments flag and ignore all characters until ')' or EOL.
// NOTE: This doesn't follow the NIST definition exactly, but is good enough for now.
// In the future, we could simply remove the items within the comments, but retain the
// comment control characters, so that the g-code parser can error-check it.
iscomment = true;
// } else if (c == ';') {
// Comment character to EOL NOT SUPPORTED. LinuxCNC definition. Not NIST.
// TODO: Install '%' feature
// } else if (c == '%') {
// Program start-end percent sign NOT SUPPORTED.
// NOTE: This maybe installed to tell Grbl when a program is running vs manual input,
// where, during a program, the system auto-cycle start will continue to execute
// everything until the next '%' sign. This will help fix resuming issues with certain
// functions that empty the planner buffer to execute its task on-time.
} else if (char_counter >= (LINE_BUFFER_SIZE-1)) {
// Detect line buffer overflow. Report error and reset line buffer.
report_status_message(STATUS_OVERFLOW);
iscomment = false;
char_counter = 0;
} else if (c >= 'a' && c <= 'z') { // Upcase lowercase
line[char_counter++] = c-'a'+'A';
} else {
line[char_counter++] = c;
}
}
}
}
// If there are no more characters in the serial read buffer to be processed and executed,
// this indicates that g-code streaming has either filled the planner buffer or has
// completed. In either case, auto-cycle start, if enabled, any queued moves.
protocol_auto_cycle_start();
protocol_execute_realtime(); // Runtime command check point.
if (sys.abort) { return; } // Bail to main() program loop to reset system.
}
return; /* Never reached */
}
// Executes run-time commands, when required. This is called from various check points in the main
// program, primarily where there may be a while loop waiting for a buffer to clear space or any
// point where the execution time from the last check point may be more than a fraction of a second.
// This is a way to execute realtime commands asynchronously (aka multitasking) with grbl's g-code
// parsing and planning functions. This function also serves as an interface for the interrupts to
// set the system realtime flags, where only the main program handles them, removing the need to
// define more computationally-expensive volatile variables. This also provides a controlled way to
// execute certain tasks without having two or more instances of the same task, such as the planner
// recalculating the buffer upon a feedhold or override.
// NOTE: The sys.rt_exec_state variable flags are set by any process, step or serial interrupts, pinouts,
// limit switches, or the main program.
void protocol_execute_realtime()
{
uint8_t rt_exec; // Temp variable to avoid calling volatile multiple times.
do { // If system is suspended, suspend loop restarts here.
// Check and execute alarms.
rt_exec = sys.rt_exec_alarm; // Copy volatile sys.rt_exec_alarm.
if (rt_exec) { // Enter only if any bit flag is true
// System alarm. Everything has shutdown by something that has gone severely wrong. Report
// the source of the error to the user. If critical, Grbl disables by entering an infinite
// loop until system reset/abort.
sys.state = STATE_ALARM; // Set system alarm state
if (rt_exec & EXEC_ALARM_HARD_LIMIT) {
report_alarm_message(ALARM_HARD_LIMIT_ERROR);
} else if (rt_exec & EXEC_ALARM_SOFT_LIMIT) {
report_alarm_message(ALARM_SOFT_LIMIT_ERROR);
} else if (rt_exec & EXEC_ALARM_ABORT_CYCLE) {
report_alarm_message(ALARM_ABORT_CYCLE);
} else if (rt_exec & EXEC_ALARM_PROBE_FAIL) {
report_alarm_message(ALARM_PROBE_FAIL);
} else if (rt_exec & EXEC_ALARM_HOMING_FAIL) {
report_alarm_message(ALARM_HOMING_FAIL);
}
// Halt everything upon a critical event flag. Currently hard and soft limits flag this.
if (rt_exec & EXEC_CRITICAL_EVENT) {
report_feedback_message(MESSAGE_CRITICAL_EVENT);
bit_false_atomic(sys.rt_exec_state,EXEC_RESET); // Disable any existing reset
do {
// Nothing. Block EVERYTHING until user issues reset or power cycles. Hard limits
// typically occur while unattended or not paying attention. Gives the user time
// to do what is needed before resetting, like killing the incoming stream. The
// same could be said about soft limits. While the position is not lost, the incoming
// stream could be still engaged and cause a serious crash if it continues afterwards.
// if (sys.rt_exec_state & EXEC_STATUS_REPORT) {
// report_realtime_status();
// bit_false_atomic(sys.rt_exec_state,EXEC_STATUS_REPORT);
// }
} while (bit_isfalse(sys.rt_exec_state,EXEC_RESET));
}
bit_false_atomic(sys.rt_exec_alarm,0xFF); // Clear all alarm flags
}
// Check amd execute realtime commands
rt_exec = sys.rt_exec_state; // Copy volatile sys.rt_exec_state.
if (rt_exec) { // Enter only if any bit flag is true
// Execute system abort.
if (rt_exec & EXEC_RESET) {
sys.abort = true; // Only place this is set true.
return; // Nothing else to do but exit.
}
// Execute and serial print status
if (rt_exec & EXEC_STATUS_REPORT) {
report_realtime_status();
bit_false_atomic(sys.rt_exec_state,EXEC_STATUS_REPORT);
}
// Execute hold states.
// NOTE: The math involved to calculate the hold should be low enough for most, if not all,
// operational scenarios. Once hold is initiated, the system enters a suspend state to block
// all main program processes until either reset or resumed.
if (rt_exec & (EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR)) {
// TODO: CHECK MODE? How to handle this? Likely nothing, since it only works when IDLE and then resets Grbl.
// State check for allowable states for hold methods.
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_MOTION_CANCEL | STATE_HOLD | STATE_SAFETY_DOOR))) {
// If in CYCLE state, all hold states immediately initiate a motion HOLD.
if (sys.state == STATE_CYCLE) {
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
sys.suspend = SUSPEND_ENABLE_HOLD; // Initiate holding cycle with flag.
}
// If IDLE, Grbl is not in motion. Simply indicate suspend ready state.
if (sys.state == STATE_IDLE) { sys.suspend = SUSPEND_ENABLE_READY; }
// Execute and flag a motion cancel with deceleration and return to idle. Used primarily by probing cycle
// to halt and cancel the remainder of the motion.
if (rt_exec & EXEC_MOTION_CANCEL) {
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
// to hold the CYCLE. If so, only flag that motion cancel is complete.
if (sys.state == STATE_CYCLE) { sys.state = STATE_MOTION_CANCEL; }
sys.suspend |= SUSPEND_MOTION_CANCEL; // Indicate motion cancel when resuming. Special motion complete.
}
// Execute a feed hold with deceleration, only during cycle.
if (rt_exec & EXEC_FEED_HOLD) {
// Block SAFETY_DOOR state from prematurely changing back to HOLD.
if (bit_isfalse(sys.state,STATE_SAFETY_DOOR)) { sys.state = STATE_HOLD; }
}
// Execute a safety door stop with a feed hold, only during a cycle, and disable spindle/coolant.
// NOTE: Safety door differs from feed holds by stopping everything no matter state, disables powered
// devices (spindle/coolant), and blocks resuming until switch is re-engaged. The power-down is
// executed here, if IDLE, or when the CYCLE completes via the EXEC_CYCLE_STOP flag.
if (rt_exec & EXEC_SAFETY_DOOR) {
report_feedback_message(MESSAGE_SAFETY_DOOR_AJAR);
// If already in active, ready-to-resume HOLD, set CYCLE_STOP flag to force de-energize.
// NOTE: Only temporarily sets the 'rt_exec' variable, not the volatile 'rt_exec_state' variable.
if (sys.suspend & SUSPEND_ENABLE_READY) { bit_true(rt_exec,EXEC_CYCLE_STOP); }
sys.suspend |= SUSPEND_ENERGIZE;
sys.state = STATE_SAFETY_DOOR;
}
}
bit_false_atomic(sys.rt_exec_state,(EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR));
}
// Execute a cycle start by starting the stepper interrupt to begin executing the blocks in queue.
if (rt_exec & EXEC_CYCLE_START) {
// Block if called at same time as the hold commands: feed hold, motion cancel, and safety door.
// Ensures auto-cycle-start doesn't resume a hold without an explicit user-input.
if (!(rt_exec & (EXEC_FEED_HOLD | EXEC_MOTION_CANCEL | EXEC_SAFETY_DOOR))) {
// Cycle start only when IDLE or when a hold is complete and ready to resume.
// NOTE: SAFETY_DOOR is implicitly blocked. It reverts to HOLD when the door is closed.
if ((sys.state == STATE_IDLE) || ((sys.state & (STATE_HOLD | STATE_MOTION_CANCEL)) && (sys.suspend & SUSPEND_ENABLE_READY))) {
// Re-energize powered components, if disabled by SAFETY_DOOR.
if (sys.suspend & SUSPEND_ENERGIZE) {
// Delayed Tasks: Restart spindle and coolant, delay to power-up, then resume cycle.
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
spindle_set_state(gc_state.modal.spindle, gc_state.spindle_speed);
delay_ms(SAFETY_DOOR_SPINDLE_DELAY); // TODO: Blocking function call. Need a non-blocking one eventually.
}
if (gc_state.modal.coolant != COOLANT_DISABLE) {
coolant_set_state(gc_state.modal.coolant);
delay_ms(SAFETY_DOOR_COOLANT_DELAY); // TODO: Blocking function call. Need a non-blocking one eventually.
}
// TODO: Install return to pre-park position.
}
// Start cycle only if queued motions exist in planner buffer and the motion is not canceled.
if (plan_get_current_block() && bit_isfalse(sys.suspend,SUSPEND_MOTION_CANCEL)) {
sys.state = STATE_CYCLE;
st_prep_buffer(); // Initialize step segment buffer before beginning cycle.
st_wake_up();
} else { // Otherwise, do nothing. Set and resume IDLE state.
sys.state = STATE_IDLE;
}
sys.suspend = SUSPEND_DISABLE; // Break suspend state.
}
}
bit_false_atomic(sys.rt_exec_state,EXEC_CYCLE_START);
}
// Reinitializes the cycle plan and stepper system after a feed hold for a resume. Called by
// realtime command execution in the main program, ensuring that the planner re-plans safely.
// NOTE: Bresenham algorithm variables are still maintained through both the planner and stepper
// cycle reinitializations. The stepper path should continue exactly as if nothing has happened.
// NOTE: EXEC_CYCLE_STOP is set by the stepper subsystem when a cycle or feed hold completes.
if (rt_exec & EXEC_CYCLE_STOP) {
if (sys.state & (STATE_HOLD | STATE_SAFETY_DOOR)) {
// Hold complete. Set to indicate ready to resume. Remain in HOLD or DOOR states until user
// has issued a resume command or reset.
if (sys.suspend & SUSPEND_ENERGIZE) { // De-energize system if safety door has been opened.
spindle_stop();
coolant_stop();
// TODO: Install parking motion here.
}
bit_true(sys.suspend,SUSPEND_ENABLE_READY);
} else { // Motion is complete. Includes CYCLE, HOMING, and MOTION_CANCEL states.
sys.suspend = SUSPEND_DISABLE;
sys.state = STATE_IDLE;
}
bit_false_atomic(sys.rt_exec_state,EXEC_CYCLE_STOP);
}
}
// Overrides flag byte (sys.override) and execution should be installed here, since they
// are realtime and require a direct and controlled interface to the main stepper program.
// Reload step segment buffer
if (sys.state & (STATE_CYCLE | STATE_HOLD | STATE_MOTION_CANCEL | STATE_SAFETY_DOOR | STATE_HOMING)) { st_prep_buffer(); }
// If safety door was opened, actively check when safety door is closed and ready to resume.
// NOTE: This unlocks the SAFETY_DOOR state to a HOLD state, such that CYCLE_START can activate a resume.
if (sys.state == STATE_SAFETY_DOOR) {
if (bit_istrue(sys.suspend,SUSPEND_ENABLE_READY)) {
if (!(system_check_safety_door_ajar())) {
sys.state = STATE_HOLD; // Update to HOLD state to indicate door is closed and ready to resume.
}
}
}
} while(sys.suspend); // Check for system suspend state before exiting.
}
// Block until all buffered steps are executed or in a cycle state. Works with feed hold
// during a synchronize call, if it should happen. Also, waits for clean cycle end.
void protocol_buffer_synchronize()
{
// If system is queued, ensure cycle resumes if the auto start flag is present.
protocol_auto_cycle_start();
do {
protocol_execute_realtime(); // Check and execute run-time commands
if (sys.abort) { return; } // Check for system abort
} while (plan_get_current_block() || (sys.state == STATE_CYCLE));
}
// Auto-cycle start has two purposes: 1. Resumes a plan_synchronize() call from a function that
// requires the planner buffer to empty (spindle enable, dwell, etc.) 2. As a user setting that
// automatically begins the cycle when a user enters a valid motion command manually. This is
// intended as a beginners feature to help new users to understand g-code. It can be disabled
// as a beginner tool, but (1.) still operates. If disabled, the operation of cycle start is
// manually issuing a cycle start command whenever the user is ready and there is a valid motion
// command in the planner queue.
// NOTE: This function is called from the main loop, buffer sync, and mc_line() only and executes
// when one of these conditions exist respectively: There are no more blocks sent (i.e. streaming
// is finished, single commands), a command that needs to wait for the motions in the buffer to
// execute calls a buffer sync, or the planner buffer is full and ready to go.
void protocol_auto_cycle_start() { bit_true_atomic(sys.rt_exec_state, EXEC_CYCLE_START); }

View File

@ -1,8 +1,9 @@
/* /*
protocol.h - controls Grbl execution protocol and procedures protocol.h - controls Grbl execution protocol and procedures
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef protocol_h #ifndef protocol_h
#define protocol_h #define protocol_h
@ -41,8 +36,8 @@
// them as they complete. It is also responsible for finishing the initialization procedures. // them as they complete. It is also responsible for finishing the initialization procedures.
void protocol_main_loop(); void protocol_main_loop();
// Checks and executes a runtime command at various stop points in main program // Checks and executes a realtime command at various stop points in main program
void protocol_execute_runtime(); void protocol_execute_realtime();
// Notify the stepper subsystem to start executing the g-code program in buffer. // Notify the stepper subsystem to start executing the g-code program in buffer.
// void protocol_cycle_start(); // void protocol_cycle_start();

View File

@ -1,8 +1,8 @@
/* /*
report.c - reporting and messaging methods report.c - reporting and messaging methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -26,16 +26,7 @@
methods to accomodate their needs. methods to accomodate their needs.
*/ */
#include "system.h" #include "grbl.h"
#include "report.h"
#include "print.h"
#include "settings.h"
#include "gcode.h"
#include "coolant_control.h"
#include "planner.h"
#include "spindle_control.h"
#include "stepper.h"
#include "serial.h"
// Handles the primary confirmation protocol response for streaming interfaces and human-feedback. // Handles the primary confirmation protocol response for streaming interfaces and human-feedback.
@ -52,42 +43,49 @@ void report_status_message(uint8_t status_code)
printPgmString(PSTR("ok\r\n")); printPgmString(PSTR("ok\r\n"));
} else { } else {
printPgmString(PSTR("error: ")); printPgmString(PSTR("error: "));
switch(status_code) { #ifdef REPORT_GUI_MODE
case STATUS_EXPECTED_COMMAND_LETTER: print_uint8_base10(status_code);
printPgmString(PSTR("Expected command letter")); break; #else
case STATUS_BAD_NUMBER_FORMAT: switch(status_code) {
printPgmString(PSTR("Bad number format")); break; case STATUS_EXPECTED_COMMAND_LETTER:
case STATUS_INVALID_STATEMENT: printPgmString(PSTR("Expected command letter")); break;
printPgmString(PSTR("Invalid statement")); break; case STATUS_BAD_NUMBER_FORMAT:
case STATUS_NEGATIVE_VALUE: printPgmString(PSTR("Bad number format")); break;
printPgmString(PSTR("Value < 0")); break; case STATUS_INVALID_STATEMENT:
case STATUS_SETTING_DISABLED: printPgmString(PSTR("Invalid statement")); break;
printPgmString(PSTR("Setting disabled")); break; case STATUS_NEGATIVE_VALUE:
case STATUS_SETTING_STEP_PULSE_MIN: printPgmString(PSTR("Value < 0")); break;
printPgmString(PSTR("Value < 3 usec")); break; case STATUS_SETTING_DISABLED:
case STATUS_SETTING_READ_FAIL: printPgmString(PSTR("Setting disabled")); break;
printPgmString(PSTR("EEPROM read fail. Using defaults")); break; case STATUS_SETTING_STEP_PULSE_MIN:
case STATUS_IDLE_ERROR: printPgmString(PSTR("Value < 3 usec")); break;
printPgmString(PSTR("Not idle")); break; case STATUS_SETTING_READ_FAIL:
case STATUS_ALARM_LOCK: printPgmString(PSTR("EEPROM read fail. Using defaults")); break;
printPgmString(PSTR("Alarm lock")); break; case STATUS_IDLE_ERROR:
case STATUS_SOFT_LIMIT_ERROR: printPgmString(PSTR("Not idle")); break;
printPgmString(PSTR("Homing not enabled")); break; case STATUS_ALARM_LOCK:
case STATUS_OVERFLOW: printPgmString(PSTR("Alarm lock")); break;
printPgmString(PSTR("Line overflow")); break; case STATUS_SOFT_LIMIT_ERROR:
printPgmString(PSTR("Homing not enabled")); break;
// Common g-code parser errors. case STATUS_OVERFLOW:
case STATUS_GCODE_MODAL_GROUP_VIOLATION: printPgmString(PSTR("Line overflow")); break;
printPgmString(PSTR("Modal group violation")); break; #ifdef MAX_STEP_RATE_HZ
case STATUS_GCODE_UNSUPPORTED_COMMAND: case STATUS_MAX_STEP_RATE_EXCEEDED:
printPgmString(PSTR("Unsupported command")); break; printPgmString(PSTR("Step rate > 30kHz")); break;
case STATUS_GCODE_UNDEFINED_FEED_RATE: #endif
printPgmString(PSTR("Undefined feed rate")); break; // Common g-code parser errors.
default: case STATUS_GCODE_MODAL_GROUP_VIOLATION:
// Remaining g-code parser errors with error codes printPgmString(PSTR("Modal group violation")); break;
printPgmString(PSTR("Invalid gcode ID:")); case STATUS_GCODE_UNSUPPORTED_COMMAND:
print_uint8_base10(status_code); // Print error code for user reference printPgmString(PSTR("Unsupported command")); break;
} case STATUS_GCODE_UNDEFINED_FEED_RATE:
printPgmString(PSTR("Undefined feed rate")); break;
default:
// Remaining g-code parser errors with error codes
printPgmString(PSTR("Invalid gcode ID:"));
print_uint8_base10(status_code); // Print error code for user reference
}
#endif
printPgmString(PSTR("\r\n")); printPgmString(PSTR("\r\n"));
} }
} }
@ -96,14 +94,22 @@ void report_status_message(uint8_t status_code)
void report_alarm_message(int8_t alarm_code) void report_alarm_message(int8_t alarm_code)
{ {
printPgmString(PSTR("ALARM: ")); printPgmString(PSTR("ALARM: "));
switch (alarm_code) { #ifdef REPORT_GUI_MODE
case ALARM_LIMIT_ERROR: print_uint8_base10(alarm_code);
printPgmString(PSTR("Hard/soft limit")); break; #else
case ALARM_ABORT_CYCLE: switch (alarm_code) {
printPgmString(PSTR("Abort during cycle")); break; case ALARM_HARD_LIMIT_ERROR:
case ALARM_PROBE_FAIL: printPgmString(PSTR("Hard limit")); break;
printPgmString(PSTR("Probe fail")); break; case ALARM_SOFT_LIMIT_ERROR:
} printPgmString(PSTR("Soft limit")); break;
case ALARM_ABORT_CYCLE:
printPgmString(PSTR("Abort during cycle")); break;
case ALARM_PROBE_FAIL:
printPgmString(PSTR("Probe fail")); break;
case ALARM_HOMING_FAIL:
printPgmString(PSTR("Homing fail")); break;
}
#endif
printPgmString(PSTR("\r\n")); printPgmString(PSTR("\r\n"));
delay_ms(500); // Force delay to ensure message clears serial write buffer. delay_ms(500); // Force delay to ensure message clears serial write buffer.
} }
@ -128,6 +134,8 @@ void report_feedback_message(uint8_t message_code)
printPgmString(PSTR("Enabled")); break; printPgmString(PSTR("Enabled")); break;
case MESSAGE_DISABLED: case MESSAGE_DISABLED:
printPgmString(PSTR("Disabled")); break; printPgmString(PSTR("Disabled")); break;
case MESSAGE_SAFETY_DOOR_AJAR:
printPgmString(PSTR("Check Door")); break;
} }
printPgmString(PSTR("]\r\n")); printPgmString(PSTR("]\r\n"));
} }
@ -141,20 +149,22 @@ void report_init_message()
// Grbl help message // Grbl help message
void report_grbl_help() { void report_grbl_help() {
printPgmString(PSTR("$$ (view Grbl settings)\r\n" #ifndef REPORT_GUI_MODE
"$# (view # parameters)\r\n" printPgmString(PSTR("$$ (view Grbl settings)\r\n"
"$G (view parser state)\r\n" "$# (view # parameters)\r\n"
"$I (view build info)\r\n" "$G (view parser state)\r\n"
"$N (view startup blocks)\r\n" "$I (view build info)\r\n"
"$x=value (save Grbl setting)\r\n" "$N (view startup blocks)\r\n"
"$Nx=line (save startup block)\r\n" "$x=value (save Grbl setting)\r\n"
"$C (check gcode mode)\r\n" "$Nx=line (save startup block)\r\n"
"$X (kill alarm lock)\r\n" "$C (check gcode mode)\r\n"
"$H (run homing cycle)\r\n" "$X (kill alarm lock)\r\n"
"~ (cycle start)\r\n" "$H (run homing cycle)\r\n"
"! (feed hold)\r\n" "~ (cycle start)\r\n"
"? (current status)\r\n" "! (feed hold)\r\n"
"ctrl-x (reset Grbl)\r\n")); "? (current status)\r\n"
"ctrl-x (reset Grbl)\r\n"));
#endif
} }
@ -162,31 +172,53 @@ void report_grbl_help() {
// NOTE: The numbering scheme here must correlate to storing in settings.c // NOTE: The numbering scheme here must correlate to storing in settings.c
void report_grbl_settings() { void report_grbl_settings() {
// Print Grbl settings. // Print Grbl settings.
printPgmString(PSTR("$0=")); print_uint8_base10(settings.pulse_microseconds); #ifdef REPORT_GUI_MODE
printPgmString(PSTR(" (step pulse, usec)\r\n$1=")); print_uint8_base10(settings.stepper_idle_lock_time); printPgmString(PSTR("$0=")); print_uint8_base10(settings.pulse_microseconds);
printPgmString(PSTR(" (step idle delay, msec)\r\n$2=")); print_uint8_base10(settings.step_invert_mask); printPgmString(PSTR("\r\n$1=")); print_uint8_base10(settings.stepper_idle_lock_time);
printPgmString(PSTR(" (step port invert mask:")); print_uint8_base2(settings.step_invert_mask); printPgmString(PSTR("\r\n$2=")); print_uint8_base10(settings.step_invert_mask);
printPgmString(PSTR(")\r\n$3=")); print_uint8_base10(settings.dir_invert_mask); printPgmString(PSTR("\r\n$3=")); print_uint8_base10(settings.dir_invert_mask);
printPgmString(PSTR(" (dir port invert mask:")); print_uint8_base2(settings.dir_invert_mask); printPgmString(PSTR("\r\n$4=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
printPgmString(PSTR(")\r\n$4=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)); printPgmString(PSTR("\r\n$5=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS));
printPgmString(PSTR(" (step enable invert, bool)\r\n$5=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)); printPgmString(PSTR("\r\n$6=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN));
printPgmString(PSTR(" (limit pins invert, bool)\r\n$6=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN)); printPgmString(PSTR("\r\n$10=")); print_uint8_base10(settings.status_report_mask);
printPgmString(PSTR(" (probe pin invert, bool)\r\n$10=")); print_uint8_base10(settings.status_report_mask); printPgmString(PSTR("\r\n$11=")); printFloat_SettingValue(settings.junction_deviation);
printPgmString(PSTR(" (status report mask:")); print_uint8_base2(settings.status_report_mask); printPgmString(PSTR("\r\n$12=")); printFloat_SettingValue(settings.arc_tolerance);
printPgmString(PSTR(")\r\n$11=")); printFloat_SettingValue(settings.junction_deviation); printPgmString(PSTR("\r\n$13=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
printPgmString(PSTR(" (junction deviation, mm)\r\n$12=")); printFloat_SettingValue(settings.arc_tolerance); printPgmString(PSTR("\r\n$20=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE));
printPgmString(PSTR(" (arc tolerance, mm)\r\n$13=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)); printPgmString(PSTR("\r\n$21=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
printPgmString(PSTR(" (report inches, bool)\r\n$14=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_AUTO_START)); printPgmString(PSTR("\r\n$22=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
printPgmString(PSTR(" (auto start, bool)\r\n$20=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)); printPgmString(PSTR("\r\n$23=")); print_uint8_base10(settings.homing_dir_mask);
printPgmString(PSTR(" (soft limits, bool)\r\n$21=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE)); printPgmString(PSTR("\r\n$24=")); printFloat_SettingValue(settings.homing_feed_rate);
printPgmString(PSTR(" (hard limits, bool)\r\n$22=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)); printPgmString(PSTR("\r\n$25=")); printFloat_SettingValue(settings.homing_seek_rate);
printPgmString(PSTR(" (homing cycle, bool)\r\n$23=")); print_uint8_base10(settings.homing_dir_mask); printPgmString(PSTR("\r\n$26=")); print_uint8_base10(settings.homing_debounce_delay);
printPgmString(PSTR(" (homing dir invert mask:")); print_uint8_base2(settings.homing_dir_mask); printPgmString(PSTR("\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff);
printPgmString(PSTR(")\r\n$24=")); printFloat_SettingValue(settings.homing_feed_rate); printPgmString(PSTR("\r\n"));
printPgmString(PSTR(" (homing feed, mm/min)\r\n$25=")); printFloat_SettingValue(settings.homing_seek_rate); #else
printPgmString(PSTR(" (homing seek, mm/min)\r\n$26=")); print_uint8_base10(settings.homing_debounce_delay); printPgmString(PSTR("$0=")); print_uint8_base10(settings.pulse_microseconds);
printPgmString(PSTR(" (homing debounce, msec)\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff); printPgmString(PSTR(" (step pulse, usec)\r\n$1=")); print_uint8_base10(settings.stepper_idle_lock_time);
printPgmString(PSTR(" (homing pull-off, mm)\r\n")); printPgmString(PSTR(" (step idle delay, msec)\r\n$2=")); print_uint8_base10(settings.step_invert_mask);
printPgmString(PSTR(" (step port invert mask:")); print_uint8_base2(settings.step_invert_mask);
printPgmString(PSTR(")\r\n$3=")); print_uint8_base10(settings.dir_invert_mask);
printPgmString(PSTR(" (dir port invert mask:")); print_uint8_base2(settings.dir_invert_mask);
printPgmString(PSTR(")\r\n$4=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
printPgmString(PSTR(" (step enable invert, bool)\r\n$5=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS));
printPgmString(PSTR(" (limit pins invert, bool)\r\n$6=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN));
printPgmString(PSTR(" (probe pin invert, bool)\r\n$10=")); print_uint8_base10(settings.status_report_mask);
printPgmString(PSTR(" (status report mask:")); print_uint8_base2(settings.status_report_mask);
printPgmString(PSTR(")\r\n$11=")); printFloat_SettingValue(settings.junction_deviation);
printPgmString(PSTR(" (junction deviation, mm)\r\n$12=")); printFloat_SettingValue(settings.arc_tolerance);
printPgmString(PSTR(" (arc tolerance, mm)\r\n$13=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
printPgmString(PSTR(" (report inches, bool)\r\n$20=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE));
printPgmString(PSTR(" (soft limits, bool)\r\n$21=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
printPgmString(PSTR(" (hard limits, bool)\r\n$22=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
printPgmString(PSTR(" (homing cycle, bool)\r\n$23=")); print_uint8_base10(settings.homing_dir_mask);
printPgmString(PSTR(" (homing dir invert mask:")); print_uint8_base2(settings.homing_dir_mask);
printPgmString(PSTR(")\r\n$24=")); printFloat_SettingValue(settings.homing_feed_rate);
printPgmString(PSTR(" (homing feed, mm/min)\r\n$25=")); printFloat_SettingValue(settings.homing_seek_rate);
printPgmString(PSTR(" (homing seek, mm/min)\r\n$26=")); print_uint8_base10(settings.homing_debounce_delay);
printPgmString(PSTR(" (homing debounce, msec)\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff);
printPgmString(PSTR(" (homing pull-off, mm)\r\n"));
#endif
// Print axis settings // Print axis settings
uint8_t idx, set_idx; uint8_t idx, set_idx;
@ -202,19 +234,23 @@ void report_grbl_settings() {
case 2: printFloat_SettingValue(settings.acceleration[idx]/(60*60)); break; case 2: printFloat_SettingValue(settings.acceleration[idx]/(60*60)); break;
case 3: printFloat_SettingValue(-settings.max_travel[idx]); break; case 3: printFloat_SettingValue(-settings.max_travel[idx]); break;
} }
printPgmString(PSTR(" (")); #ifdef REPORT_GUI_MODE
switch (idx) { printPgmString(PSTR("\r\n"));
case X_AXIS: printPgmString(PSTR("x")); break; #else
case Y_AXIS: printPgmString(PSTR("y")); break; printPgmString(PSTR(" ("));
case Z_AXIS: printPgmString(PSTR("z")); break; switch (idx) {
} case X_AXIS: printPgmString(PSTR("x")); break;
switch (set_idx) { case Y_AXIS: printPgmString(PSTR("y")); break;
case 0: printPgmString(PSTR(", step/mm")); break; case Z_AXIS: printPgmString(PSTR("z")); break;
case 1: printPgmString(PSTR(" max rate, mm/min")); break; }
case 2: printPgmString(PSTR(" accel, mm/sec^2")); break; switch (set_idx) {
case 3: printPgmString(PSTR(" max travel, mm")); break; case 0: printPgmString(PSTR(", step/mm")); break;
} case 1: printPgmString(PSTR(" max rate, mm/min")); break;
printPgmString(PSTR(")\r\n")); case 2: printPgmString(PSTR(" accel, mm/sec^2")); break;
case 3: printPgmString(PSTR(" max travel, mm")); break;
}
printPgmString(PSTR(")\r\n"));
#endif
} }
val += AXIS_SETTINGS_INCREMENT; val += AXIS_SETTINGS_INCREMENT;
} }
@ -232,10 +268,12 @@ void report_probe_parameters()
// Report in terms of machine position. // Report in terms of machine position.
printPgmString(PSTR("[PRB:")); printPgmString(PSTR("[PRB:"));
for (i=0; i< N_AXIS; i++) { for (i=0; i< N_AXIS; i++) {
print_position[i] = sys.probe_position[i]/settings.steps_per_mm[i]; print_position[i] = system_convert_axis_steps_to_mpos(sys.probe_position,i);
printFloat_CoordValue(print_position[i]); printFloat_CoordValue(print_position[i]);
if (i < (N_AXIS-1)) { printPgmString(PSTR(",")); } if (i < (N_AXIS-1)) { printPgmString(PSTR(",")); }
} }
printPgmString(PSTR(":"));
print_uint8_base10(sys.probe_succeeded);
printPgmString(PSTR("]\r\n")); printPgmString(PSTR("]\r\n"));
} }
@ -279,12 +317,17 @@ void report_ngc_parameters()
// Print current gcode parser mode state // Print current gcode parser mode state
void report_gcode_modes() void report_gcode_modes()
{ {
printPgmString(PSTR("["));
switch (gc_state.modal.motion) { switch (gc_state.modal.motion) {
case MOTION_MODE_SEEK : printPgmString(PSTR("[G0")); break; case MOTION_MODE_SEEK : printPgmString(PSTR("G0")); break;
case MOTION_MODE_LINEAR : printPgmString(PSTR("[G1")); break; case MOTION_MODE_LINEAR : printPgmString(PSTR("G1")); break;
case MOTION_MODE_CW_ARC : printPgmString(PSTR("[G2")); break; case MOTION_MODE_CW_ARC : printPgmString(PSTR("G2")); break;
case MOTION_MODE_CCW_ARC : printPgmString(PSTR("[G3")); break; case MOTION_MODE_CCW_ARC : printPgmString(PSTR("G3")); break;
case MOTION_MODE_NONE : printPgmString(PSTR("[G80")); break; case MOTION_MODE_NONE : printPgmString(PSTR("G80")); break;
default:
printPgmString(PSTR("G38."));
print_uint8_base10(gc_state.modal.motion - (MOTION_MODE_PROBE_TOWARD+2));
} }
printPgmString(PSTR(" G")); printPgmString(PSTR(" G"));
@ -331,6 +374,11 @@ void report_gcode_modes()
printPgmString(PSTR(" F")); printPgmString(PSTR(" F"));
printFloat_RateValue(gc_state.feed_rate); printFloat_RateValue(gc_state.feed_rate);
#ifdef VARIABLE_SPINDLE
printPgmString(PSTR(" S"));
printFloat_RateValue(gc_state.spindle_speed);
#endif
printPgmString(PSTR("]\r\n")); printPgmString(PSTR("]\r\n"));
} }
@ -371,27 +419,23 @@ void report_realtime_status()
// Report current machine state // Report current machine state
switch (sys.state) { switch (sys.state) {
case STATE_IDLE: printPgmString(PSTR("<Idle")); break; case STATE_IDLE: printPgmString(PSTR("<Idle")); break;
case STATE_QUEUED: printPgmString(PSTR("<Queue")); break; case STATE_MOTION_CANCEL: // Report run state.
case STATE_CYCLE: printPgmString(PSTR("<Run")); break; case STATE_CYCLE: printPgmString(PSTR("<Run")); break;
case STATE_HOLD: printPgmString(PSTR("<Hold")); break; case STATE_HOLD: printPgmString(PSTR("<Hold")); break;
case STATE_HOMING: printPgmString(PSTR("<Home")); break; case STATE_HOMING: printPgmString(PSTR("<Home")); break;
case STATE_ALARM: printPgmString(PSTR("<Alarm")); break; case STATE_ALARM: printPgmString(PSTR("<Alarm")); break;
case STATE_CHECK_MODE: printPgmString(PSTR("<Check")); break; case STATE_CHECK_MODE: printPgmString(PSTR("<Check")); break;
case STATE_SAFETY_DOOR: printPgmString(PSTR("<Door")); break;
} }
// If reporting a position, convert the current step count (current_position) to millimeters. // If reporting a position, convert the current step count (current_position) to millimeters.
if (bit_istrue(settings.status_report_mask,(BITFLAG_RT_STATUS_MACHINE_POSITION | BITFLAG_RT_STATUS_WORK_POSITION))) { if (bit_istrue(settings.status_report_mask,(BITFLAG_RT_STATUS_MACHINE_POSITION | BITFLAG_RT_STATUS_WORK_POSITION))) {
for (i=0; i< N_AXIS; i++) { print_position[i] = current_position[i]/settings.steps_per_mm[i]; } system_convert_array_steps_to_mpos(print_position,current_position);
} }
// Report machine position // Report machine position
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_MACHINE_POSITION)) { if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_MACHINE_POSITION)) {
printPgmString(PSTR(",MPos:")); printPgmString(PSTR(",MPos:"));
// print_position[X_AXIS] = 0.5*current_position[X_AXIS]/settings.steps_per_mm[X_AXIS];
// print_position[Z_AXIS] = 0.5*current_position[Y_AXIS]/settings.steps_per_mm[Y_AXIS];
// print_position[Y_AXIS] = print_position[X_AXIS]-print_position[Z_AXIS]);
// print_position[X_AXIS] -= print_position[Z_AXIS];
// print_position[Z_AXIS] = current_position[Z_AXIS]/settings.steps_per_mm[Z_AXIS];
for (i=0; i< N_AXIS; i++) { for (i=0; i< N_AXIS; i++) {
printFloat_CoordValue(print_position[i]); printFloat_CoordValue(print_position[i]);
if (i < (N_AXIS-1)) { printPgmString(PSTR(",")); } if (i < (N_AXIS-1)) { printPgmString(PSTR(",")); }
@ -439,5 +483,19 @@ void report_realtime_status()
printFloat_RateValue(st_get_realtime_rate()); printFloat_RateValue(st_get_realtime_rate());
#endif #endif
#ifdef REPORT_LIMIT_PIN_STATE
printPgmString(PSTR(",Lim:"));
uint8_t idx;
for (idx=0; idx<N_AXIS; idx++) {
if (LIMIT_PIN & get_limit_pin_mask(idx)) { printString(PSTR("1")); }
else { printString(PSTR("0")); }
}
#endif
#ifdef REPORT_CONTROL_PIN_STATE
printPgmString(PSTR(",Ctl:"));
print_uint8_base2(CONTROL_PIN & CONTROL_MASK);
#endif
printPgmString(PSTR(">\r\n")); printPgmString(PSTR(">\r\n"));
} }

View File

@ -1,8 +1,8 @@
/* /*
report.h - reporting and messaging methods report.h - reporting and messaging methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -33,6 +33,7 @@
#define STATUS_ALARM_LOCK 9 #define STATUS_ALARM_LOCK 9
#define STATUS_SOFT_LIMIT_ERROR 10 #define STATUS_SOFT_LIMIT_ERROR 10
#define STATUS_OVERFLOW 11 #define STATUS_OVERFLOW 11
#define STATUS_MAX_STEP_RATE_EXCEEDED 12
#define STATUS_GCODE_UNSUPPORTED_COMMAND 20 #define STATUS_GCODE_UNSUPPORTED_COMMAND 20
#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21 #define STATUS_GCODE_MODAL_GROUP_VIOLATION 21
@ -53,10 +54,12 @@
#define STATUS_GCODE_UNUSED_WORDS 36 #define STATUS_GCODE_UNUSED_WORDS 36
#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37 #define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
// Define Grbl alarm codes. Less than zero to distinguish alarm error from status error. // Define Grbl alarm codes.
#define ALARM_LIMIT_ERROR -1 #define ALARM_HARD_LIMIT_ERROR 1
#define ALARM_ABORT_CYCLE -2 #define ALARM_SOFT_LIMIT_ERROR 2
#define ALARM_PROBE_FAIL -3 #define ALARM_ABORT_CYCLE 3
#define ALARM_PROBE_FAIL 4
#define ALARM_HOMING_FAIL 5
// Define Grbl feedback message codes. // Define Grbl feedback message codes.
#define MESSAGE_CRITICAL_EVENT 1 #define MESSAGE_CRITICAL_EVENT 1
@ -64,6 +67,7 @@
#define MESSAGE_ALARM_UNLOCK 3 #define MESSAGE_ALARM_UNLOCK 3
#define MESSAGE_ENABLED 4 #define MESSAGE_ENABLED 4
#define MESSAGE_DISABLED 5 #define MESSAGE_DISABLED 5
#define MESSAGE_SAFETY_DOOR_AJAR 6
// Prints system status messages. // Prints system status messages.
void report_status_message(uint8_t status_code); void report_status_message(uint8_t status_code);

View File

@ -1,8 +1,9 @@
/* /*
serial.c - Low level functions for sending and recieving bytes via the serial port serial.c - Low level functions for sending and recieving bytes via the serial port
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,18 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include <avr/interrupt.h> #include "grbl.h"
#include "system.h"
#include "serial.h"
#include "motion_control.h"
#include "protocol.h"
uint8_t serial_rx_buffer[RX_BUFFER_SIZE]; uint8_t serial_rx_buffer[RX_BUFFER_SIZE];
@ -98,7 +89,7 @@ void serial_write(uint8_t data) {
// Wait until there is space in the buffer // Wait until there is space in the buffer
while (next_head == serial_tx_buffer_tail) { while (next_head == serial_tx_buffer_tail) {
// TODO: Restructure st_prep_buffer() calls to be executed here during a long print. // TODO: Restructure st_prep_buffer() calls to be executed here during a long print.
if (sys.execute & EXEC_RESET) { return; } // Only check for abort to avoid an endless loop. if (sys.rt_exec_state & EXEC_RESET) { return; } // Only check for abort to avoid an endless loop.
} }
// Store data and advance head // Store data and advance head
@ -170,12 +161,13 @@ ISR(SERIAL_RX)
uint8_t data = UDR0; uint8_t data = UDR0;
uint8_t next_head; uint8_t next_head;
// Pick off runtime command characters directly from the serial stream. These characters are // Pick off realtime command characters directly from the serial stream. These characters are
// not passed into the buffer, but these set system state flag bits for runtime execution. // not passed into the buffer, but these set system state flag bits for realtime execution.
switch (data) { switch (data) {
case CMD_STATUS_REPORT: bit_true_atomic(sys.execute, EXEC_STATUS_REPORT); break; // Set as true case CMD_STATUS_REPORT: bit_true_atomic(sys.rt_exec_state, EXEC_STATUS_REPORT); break; // Set as true
case CMD_CYCLE_START: bit_true_atomic(sys.execute, EXEC_CYCLE_START); break; // Set as true case CMD_CYCLE_START: bit_true_atomic(sys.rt_exec_state, EXEC_CYCLE_START); break; // Set as true
case CMD_FEED_HOLD: bit_true_atomic(sys.execute, EXEC_FEED_HOLD); break; // Set as true case CMD_FEED_HOLD: bit_true_atomic(sys.rt_exec_state, EXEC_FEED_HOLD); break; // Set as true
case CMD_SAFETY_DOOR: bit_true_atomic(sys.rt_exec_state, EXEC_SAFETY_DOOR); break; // Set as true
case CMD_RESET: mc_reset(); break; // Call motion control reset routine. case CMD_RESET: mc_reset(); break; // Call motion control reset routine.
default: // Write character to buffer default: // Write character to buffer
next_head = serial_rx_buffer_head + 1; next_head = serial_rx_buffer_head + 1;

View File

@ -1,8 +1,9 @@
/* /*
serial.c - Low level functions for sending and recieving bytes via the serial port serial.c - Low level functions for sending and recieving bytes via the serial port
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef serial_h #ifndef serial_h
#define serial_h #define serial_h

View File

@ -1,8 +1,9 @@
/* /*
settings.c - eeprom configuration handling settings.c - eeprom configuration handling
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,20 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "settings.h"
#include "eeprom.h"
#include "protocol.h"
#include "report.h"
#include "limits.h"
#include "stepper.h"
settings_t settings; settings_t settings;
@ -83,7 +72,6 @@ void settings_restore_global_settings() {
settings.flags = 0; settings.flags = 0;
if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; } if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; }
if (DEFAULT_AUTO_START) { settings.flags |= BITFLAG_AUTO_START; }
if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; } if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
if (DEFAULT_INVERT_LIMIT_PINS) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; } if (DEFAULT_INVERT_LIMIT_PINS) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
if (DEFAULT_SOFT_LIMIT_ENABLE) { settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; } if (DEFAULT_SOFT_LIMIT_ENABLE) { settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; }
@ -110,7 +98,7 @@ void settings_restore_global_settings() {
// Helper function to clear the EEPROM space containing parameter data. // Helper function to clear the EEPROM space containing parameter data.
void settings_clear_parameters() { void settings_clear_parameters() {
uint8_t idx; uint8_t idx;
float coord_data[3]; float coord_data[N_AXIS];
memset(&coord_data, 0, sizeof(coord_data)); memset(&coord_data, 0, sizeof(coord_data));
for (idx=0; idx < SETTING_INDEX_NCOORD; idx++) { settings_write_coord_data(idx, coord_data); } for (idx=0; idx < SETTING_INDEX_NCOORD; idx++) { settings_write_coord_data(idx, coord_data); }
} }
@ -200,8 +188,18 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
if (parameter < N_AXIS) { if (parameter < N_AXIS) {
// Valid axis setting found. // Valid axis setting found.
switch (set_idx) { switch (set_idx) {
case 0: settings.steps_per_mm[parameter] = value; break; case 0:
case 1: settings.max_rate[parameter] = value; break; #ifdef MAX_STEP_RATE_HZ
if (value*settings.max_rate[parameter] > (MAX_STEP_RATE_HZ*60.0)) { return(STATUS_MAX_STEP_RATE_EXCEEDED); }
#endif
settings.steps_per_mm[parameter] = value;
break;
case 1:
#ifdef MAX_STEP_RATE_HZ
if (value*settings.steps_per_mm[parameter] > (MAX_STEP_RATE_HZ*60.0)) { return(STATUS_MAX_STEP_RATE_EXCEEDED); }
#endif
settings.max_rate[parameter] = value;
break;
case 2: settings.acceleration[parameter] = value*60*60; break; // Convert to mm/min^2 for grbl internal use. case 2: settings.acceleration[parameter] = value*60*60; break; // Convert to mm/min^2 for grbl internal use.
case 3: settings.max_travel[parameter] = -value; break; // Store as negative for grbl internal use. case 3: settings.max_travel[parameter] = -value; break; // Store as negative for grbl internal use.
} }
@ -248,10 +246,6 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
if (int_value) { settings.flags |= BITFLAG_REPORT_INCHES; } if (int_value) { settings.flags |= BITFLAG_REPORT_INCHES; }
else { settings.flags &= ~BITFLAG_REPORT_INCHES; } else { settings.flags &= ~BITFLAG_REPORT_INCHES; }
break; break;
case 14: // Reset to ensure change. Immediate re-init may cause problems.
if (int_value) { settings.flags |= BITFLAG_AUTO_START; }
else { settings.flags &= ~BITFLAG_AUTO_START; }
break;
case 20: case 20:
if (int_value) { if (int_value) {
if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) { return(STATUS_SOFT_LIMIT_ERROR); } if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) { return(STATUS_SOFT_LIMIT_ERROR); }

View File

@ -1,8 +1,9 @@
/* /*
settings.h - eeprom configuration handling settings.h - eeprom configuration handling
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,19 +18,12 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#ifndef settings_h #ifndef settings_h
#define settings_h #define settings_h
#include "grbl.h"
#define GRBL_VERSION "0.9g"
#define GRBL_VERSION_BUILD "20140905"
// Version of the EEPROM data. Will be used to migrate existing data from older versions of Grbl // Version of the EEPROM data. Will be used to migrate existing data from older versions of Grbl
// when firmware is upgraded. Always stored in byte 0 of eeprom // when firmware is upgraded. Always stored in byte 0 of eeprom
@ -37,7 +31,7 @@
// Define bit flag masks for the boolean settings in settings.flag. // Define bit flag masks for the boolean settings in settings.flag.
#define BITFLAG_REPORT_INCHES bit(0) #define BITFLAG_REPORT_INCHES bit(0)
#define BITFLAG_AUTO_START bit(1) // #define BITFLAG_AUTO_START bit(1) // Obsolete. Don't alter to keep back compatibility.
#define BITFLAG_INVERT_ST_ENABLE bit(2) #define BITFLAG_INVERT_ST_ENABLE bit(2)
#define BITFLAG_HARD_LIMIT_ENABLE bit(3) #define BITFLAG_HARD_LIMIT_ENABLE bit(3)
#define BITFLAG_HOMING_ENABLE bit(4) #define BITFLAG_HOMING_ENABLE bit(4)

View File

@ -1,8 +1,9 @@
/* /*
spindle_control.c - spindle control methods spindle_control.c - spindle control methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,17 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "spindle_control.h"
#include "protocol.h"
#include "gcode.h"
void spindle_init() void spindle_init()
@ -60,22 +52,16 @@ void spindle_stop()
} }
void spindle_run(uint8_t direction, float rpm) void spindle_set_state(uint8_t state, float rpm)
{ {
if (sys.state == STATE_CHECK_MODE) { return; }
// Empty planner buffer to ensure spindle is set when programmed.
protocol_auto_cycle_start(); //temp fix for M3 lockup
protocol_buffer_synchronize();
// Halt or set spindle direction and rpm. // Halt or set spindle direction and rpm.
if (direction == SPINDLE_DISABLE) { if (state == SPINDLE_DISABLE) {
spindle_stop(); spindle_stop();
} else { } else {
if (direction == SPINDLE_ENABLE_CW) { if (state == SPINDLE_ENABLE_CW) {
SPINDLE_DIRECTION_PORT &= ~(1<<SPINDLE_DIRECTION_BIT); SPINDLE_DIRECTION_PORT &= ~(1<<SPINDLE_DIRECTION_BIT);
} else { } else {
SPINDLE_DIRECTION_PORT |= (1<<SPINDLE_DIRECTION_BIT); SPINDLE_DIRECTION_PORT |= (1<<SPINDLE_DIRECTION_BIT);
@ -83,15 +69,30 @@ void spindle_run(uint8_t direction, float rpm)
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
// TODO: Install the optional capability for frequency-based output for servos. // TODO: Install the optional capability for frequency-based output for servos.
#define SPINDLE_RPM_RANGE (SPINDLE_MAX_RPM-SPINDLE_MIN_RPM) #ifdef CPU_MAP_ATMEGA2560
TCCRA_REGISTER = (1<<COMB_BIT) | (1<<WAVE1_REGISTER) | (1<<WAVE0_REGISTER); TCCRA_REGISTER = (1<<COMB_BIT) | (1<<WAVE1_REGISTER) | (1<<WAVE0_REGISTER);
TCCRB_REGISTER = (TCCRB_REGISTER & 0b11111000) | 0x02; // set to 1/8 Prescaler TCCRB_REGISTER = (TCCRB_REGISTER & 0b11111000) | 0x02 | (1<<WAVE2_REGISTER) | (1<<WAVE3_REGISTER); // set to 1/8 Prescaler
rpm -= SPINDLE_MIN_RPM; OCR4A = 0xFFFF; // set the top 16bit value
if ( rpm > SPINDLE_RPM_RANGE ) { rpm = SPINDLE_RPM_RANGE; } // Prevent uint8 overflow uint16_t current_pwm;
uint8_t current_pwm = floor( rpm*(255.0/SPINDLE_RPM_RANGE) + 0.5); #else
OCR_REGISTER = current_pwm; TCCRA_REGISTER = (1<<COMB_BIT) | (1<<WAVE1_REGISTER) | (1<<WAVE0_REGISTER);
TCCRB_REGISTER = (TCCRB_REGISTER & 0b11111000) | 0x02; // set to 1/8 Prescaler
uint8_t current_pwm;
#endif
#ifndef CPU_MAP_ATMEGA328P // On the Uno, spindle enable and PWM are shared. #define SPINDLE_RPM_RANGE (SPINDLE_MAX_RPM-SPINDLE_MIN_RPM)
if ( rpm < SPINDLE_MIN_RPM ) { rpm = 0; }
else {
rpm -= SPINDLE_MIN_RPM;
if ( rpm > SPINDLE_RPM_RANGE ) { rpm = SPINDLE_RPM_RANGE; } // Prevent integer overflow
}
current_pwm = floor( rpm*(PWM_MAX_VALUE/SPINDLE_RPM_RANGE) + 0.5);
#ifdef MINIMUM_SPINDLE_PWM
if (current_pwm < MINIMUM_SPINDLE_PWM) { current_pwm = MINIMUM_SPINDLE_PWM; }
#endif
OCR_REGISTER = current_pwm; // Set PWM pin output
#ifdef CPU_MAP_ATMEGA2560 // On the Uno, spindle enable and PWM are shared.
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT); SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT);
#endif #endif
#else #else
@ -100,3 +101,11 @@ void spindle_run(uint8_t direction, float rpm)
} }
} }
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.
spindle_set_state(state, rpm);
}

View File

@ -1,8 +1,9 @@
/* /*
spindle_control.h - spindle control methods spindle_control.h - spindle control methods
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2012-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2012 Sungeun K. Jeon
*/
#ifndef spindle_control_h #ifndef spindle_control_h
#define spindle_control_h #define spindle_control_h
@ -34,6 +29,8 @@ void spindle_init();
// Sets spindle direction and spindle rpm via PWM, if enabled. // Sets spindle direction and spindle rpm via PWM, if enabled.
void spindle_run(uint8_t direction, float rpm); void spindle_run(uint8_t direction, float rpm);
void spindle_set_state(uint8_t state, float rpm);
// Kills spindle. // Kills spindle.
void spindle_stop(); void spindle_stop();

View File

@ -1,8 +1,9 @@
/* /*
stepper.c - stepper motor driver: executes motion plans using stepper motors stepper.c - stepper motor driver: executes motion plans using stepper motors
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,19 +18,8 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include "system.h" #include "grbl.h"
#include "nuts_bolts.h"
#include "stepper.h"
#include "settings.h"
#include "planner.h"
#include "probe.h"
// Some useful constants. // Some useful constants.
@ -228,7 +218,7 @@ void st_go_idle()
// Set stepper driver idle state, disabled or enabled, depending on settings and circumstances. // Set stepper driver idle state, disabled or enabled, depending on settings and circumstances.
bool pin_state = false; // Keep enabled. bool pin_state = false; // Keep enabled.
if (((settings.stepper_idle_lock_time != 0xff) || bit_istrue(sys.execute,EXEC_ALARM)) && sys.state != STATE_HOMING) { if (((settings.stepper_idle_lock_time != 0xff) || sys.rt_exec_alarm) && sys.state != STATE_HOMING) {
// Force stepper dwell to lock axes for a defined amount of time to ensure the axes come to a complete // Force stepper dwell to lock axes for a defined amount of time to ensure the axes come to a complete
// stop and not drift from residual inertial forces at the end of the last movement. // stop and not drift from residual inertial forces at the end of the last movement.
delay_ms(settings.stepper_idle_lock_time); delay_ms(settings.stepper_idle_lock_time);
@ -351,7 +341,7 @@ ISR(TIMER1_COMPA_vect)
} else { } else {
// Segment buffer empty. Shutdown. // Segment buffer empty. Shutdown.
st_go_idle(); st_go_idle();
bit_true_atomic(sys.execute,EXEC_CYCLE_STOP); // Flag main program for cycle end bit_true_atomic(sys.rt_exec_state,EXEC_CYCLE_STOP); // Flag main program for cycle end
return; // Nothing to do but exit. return; // Nothing to do but exit.
} }
} }
@ -534,6 +524,12 @@ void st_update_plan_block_parameters()
*/ */
void st_prep_buffer() void st_prep_buffer()
{ {
if (sys.state & (STATE_HOLD|STATE_MOTION_CANCEL|STATE_SAFETY_DOOR)) {
// Check if we still need to generate more segments for a motion suspend.
if (prep.current_speed == 0.0) { return; } // Nothing to do. Bail.
}
while (segment_buffer_tail != segment_next_head) { // Check if we need to fill the buffer. while (segment_buffer_tail != segment_next_head) { // Check if we need to fill the buffer.
// Determine if we need to load a new planner block or if the block has been replanned. // Determine if we need to load a new planner block or if the block has been replanned.
@ -576,7 +572,7 @@ void st_prep_buffer()
prep.dt_remainder = 0.0; // Reset for new planner block prep.dt_remainder = 0.0; // Reset for new planner block
if (sys.state == STATE_HOLD) { if (sys.state & (STATE_HOLD|STATE_MOTION_CANCEL|STATE_SAFETY_DOOR)) {
// Override planner block entry speed and enforce deceleration during feed hold. // Override planner block entry speed and enforce deceleration during feed hold.
prep.current_speed = prep.exit_speed; prep.current_speed = prep.exit_speed;
pl_block->entry_speed_sqr = prep.exit_speed*prep.exit_speed; pl_block->entry_speed_sqr = prep.exit_speed*prep.exit_speed;
@ -592,7 +588,7 @@ void st_prep_buffer()
*/ */
prep.mm_complete = 0.0; // Default velocity profile complete at 0.0mm from end of block. prep.mm_complete = 0.0; // Default velocity profile complete at 0.0mm from end of block.
float inv_2_accel = 0.5/pl_block->acceleration; float inv_2_accel = 0.5/pl_block->acceleration;
if (sys.state == STATE_HOLD) { // [Forced Deceleration to Zero Velocity] if (sys.state & (STATE_HOLD|STATE_MOTION_CANCEL|STATE_SAFETY_DOOR)) { // [Forced Deceleration to Zero Velocity]
// Compute velocity profile parameters for a feed hold in-progress. This profile overrides // Compute velocity profile parameters for a feed hold in-progress. This profile overrides
// the planner block profile, enforcing a deceleration to zero speed. // the planner block profile, enforcing a deceleration to zero speed.
prep.ramp_type = RAMP_DECEL; prep.ramp_type = RAMP_DECEL;
@ -751,16 +747,14 @@ void st_prep_buffer()
// Bail if we are at the end of a feed hold and don't have a step to execute. // Bail if we are at the end of a feed hold and don't have a step to execute.
if (prep_segment->n_step == 0) { if (prep_segment->n_step == 0) {
if (sys.state == STATE_HOLD) { if (sys.state & (STATE_HOLD|STATE_MOTION_CANCEL|STATE_SAFETY_DOOR)) {
// Less than one step to decelerate to zero speed, but already very close. AMASS // Less than one step to decelerate to zero speed, but already very close. AMASS
// requires full steps to execute. So, just bail. // requires full steps to execute. So, just bail.
prep.current_speed = 0.0; prep.current_speed = 0.0; // NOTE: (=0.0) Used to indicate completed segment calcs for hold.
prep.dt_remainder = 0.0; prep.dt_remainder = 0.0;
prep.steps_remaining = n_steps_remaining; prep.steps_remaining = n_steps_remaining;
pl_block->millimeters = prep.steps_remaining/prep.step_per_mm; // Update with full steps. pl_block->millimeters = prep.steps_remaining/prep.step_per_mm; // Update with full steps.
plan_cycle_reinitialize(); plan_cycle_reinitialize();
sys.state = STATE_QUEUED;
return; // Segment not generated, but current step data still retained. return; // Segment not generated, but current step data still retained.
} }
} }
@ -823,21 +817,18 @@ void st_prep_buffer()
} else { } else {
// End of planner block or forced-termination. No more distance to be executed. // End of planner block or forced-termination. No more distance to be executed.
if (mm_remaining > 0.0) { // At end of forced-termination. if (mm_remaining > 0.0) { // At end of forced-termination.
// Reset prep parameters for resuming and then bail. // Reset prep parameters for resuming and then bail. Allow the stepper ISR to complete
// NOTE: Currently only feed holds qualify for this scenario. May change with overrides. // the segment queue, where realtime protocol will set new state upon receiving the
prep.current_speed = 0.0; // cycle stop flag from the ISR. Prep_segment is blocked until then.
prep.current_speed = 0.0; // NOTE: (=0.0) Used to indicate completed segment calcs for hold.
prep.dt_remainder = 0.0; prep.dt_remainder = 0.0;
prep.steps_remaining = ceil(steps_remaining); prep.steps_remaining = ceil(steps_remaining);
pl_block->millimeters = prep.steps_remaining/prep.step_per_mm; // Update with full steps. pl_block->millimeters = prep.steps_remaining/prep.step_per_mm; // Update with full steps.
plan_cycle_reinitialize(); plan_cycle_reinitialize();
sys.state = STATE_QUEUED; // End cycle.
return; // Bail! return; // Bail!
// TODO: Try to move QUEUED setting into cycle re-initialize.
} else { // End of planner block } else { // End of planner block
// The planner block is complete. All steps are set to be executed in the segment buffer. // The planner block is complete. All steps are set to be executed in the segment buffer.
pl_block = NULL; pl_block = NULL; // Set pointer to indicate check and load next planner block.
plan_discard_current_block(); plan_discard_current_block();
} }
} }
@ -846,14 +837,14 @@ void st_prep_buffer()
} }
// Called by runtime status reporting to fetch the current speed being executed. This value // Called by realtime status reporting to fetch the current speed being executed. This value
// however is not exactly the current speed, but the speed computed in the last step segment // however is not exactly the current speed, but the speed computed in the last step segment
// in the segment buffer. It will always be behind by up to the number of segment blocks (-1) // in the segment buffer. It will always be behind by up to the number of segment blocks (-1)
// divided by the ACCELERATION TICKS PER SECOND in seconds. // divided by the ACCELERATION TICKS PER SECOND in seconds.
#ifdef REPORT_REALTIME_RATE #ifdef REPORT_REALTIME_RATE
float st_get_realtime_rate() float st_get_realtime_rate()
{ {
if (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_HOLD)){ if (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_HOLD | STATE_MOTION_CANCEL | STATE_SAFETY_DOOR)){
return prep.current_speed; return prep.current_speed;
} }
return 0.0f; return 0.0f;

View File

@ -1,8 +1,9 @@
/* /*
stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
Part of Grbl v0.9 Part of Grbl
Copyright (c) 2012-2014 Sungeun K. Jeon Copyright (c) 2011-2015 Sungeun K. Jeon
Copyright (c) 2009-2011 Simen Svale Skogsrud
Grbl is free software: you can redistribute it and/or modify Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
@ -17,12 +18,6 @@
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>. along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/ */
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011 Sungeun K. Jeon
*/
#ifndef stepper_h #ifndef stepper_h
#define stepper_h #define stepper_h
@ -34,7 +29,7 @@
// Initialize and setup the stepper motor subsystem // Initialize and setup the stepper motor subsystem
void stepper_init(); void stepper_init();
// Enable steppers, but cycle does not start unless called by motion control or runtime command. // Enable steppers, but cycle does not start unless called by motion control or realtime command.
void st_wake_up(); void st_wake_up();
// Immediately disables steppers // Immediately disables steppers
@ -46,13 +41,13 @@ void st_generate_step_dir_invert_masks();
// Reset the stepper subsystem variables // Reset the stepper subsystem variables
void st_reset(); void st_reset();
// Reloads step segment buffer. Called continuously by runtime execution system. // Reloads step segment buffer. Called continuously by realtime execution system.
void st_prep_buffer(); void st_prep_buffer();
// Called by planner_recalculate() when the executing block is updated by the new plan. // Called by planner_recalculate() when the executing block is updated by the new plan.
void st_update_plan_block_parameters(); void st_update_plan_block_parameters();
// Called by runtime status reporting if realtime rate reporting is enabled in config.h. // Called by realtime status reporting if realtime rate reporting is enabled in config.h.
#ifdef REPORT_REALTIME_RATE #ifdef REPORT_REALTIME_RATE
float st_get_realtime_rate(); float st_get_realtime_rate();
#endif #endif

272
grbl/system.c Normal file
View File

@ -0,0 +1,272 @@
/*
system.c - Handles system level commands and real-time processes
Part of Grbl
Copyright (c) 2014-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "grbl.h"
void system_init()
{
CONTROL_DDR &= ~(CONTROL_MASK); // Configure as input pins
#ifdef DISABLE_CONTROL_PIN_PULL_UP
CONTROL_PORT &= ~(CONTROL_MASK); // Normal low operation. Requires external pull-down.
#else
CONTROL_PORT |= CONTROL_MASK; // Enable internal pull-up resistors. Normal high operation.
#endif
CONTROL_PCMSK |= CONTROL_MASK; // Enable specific pins of the Pin Change Interrupt
PCICR |= (1 << CONTROL_INT); // Enable Pin Change Interrupt
}
// Pin change interrupt for pin-out commands, i.e. cycle start, feed hold, and reset. Sets
// only the realtime command execute variable to have the main program execute these when
// its ready. This works exactly like the character-based realtime commands when picked off
// directly from the incoming serial data stream.
ISR(CONTROL_INT_vect)
{
uint8_t pin = (CONTROL_PIN & CONTROL_MASK);
#ifndef INVERT_CONTROL_PIN
pin ^= CONTROL_MASK;
#endif
// Enter only if any CONTROL pin is detected as active.
if (pin) {
if (bit_istrue(pin,bit(RESET_BIT))) {
mc_reset();
} else if (bit_istrue(pin,bit(CYCLE_START_BIT))) {
bit_true(sys.rt_exec_state, EXEC_CYCLE_START);
#ifndef ENABLE_SAFETY_DOOR_INPUT_PIN
} else if (bit_istrue(pin,bit(FEED_HOLD_BIT))) {
bit_true(sys.rt_exec_state, EXEC_FEED_HOLD);
#else
} else if (bit_istrue(pin,bit(SAFETY_DOOR_BIT))) {
bit_true(sys.rt_exec_state, EXEC_SAFETY_DOOR);
#endif
}
}
}
// Returns if safety door is ajar(T) or closed(F), based on pin state.
uint8_t system_check_safety_door_ajar()
{
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
#ifdef INVERT_CONTROL_PIN
return(bit_istrue(CONTROL_PIN,bit(SAFETY_DOOR_BIT)));
#else
return(bit_isfalse(CONTROL_PIN,bit(SAFETY_DOOR_BIT)));
#endif
#else
return(false); // Input pin not enabled, so just return that it's closed.
#endif
}
// Executes user startup script, if stored.
void system_execute_startup(char *line)
{
uint8_t n;
for (n=0; n < N_STARTUP_LINE; n++) {
if (!(settings_read_startup_line(n, line))) {
report_status_message(STATUS_SETTING_READ_FAIL);
} else {
if (line[0] != 0) {
printString(line); // Echo startup line to indicate execution.
report_status_message(gc_execute_line(line));
}
}
}
}
// Directs and executes one line of formatted input from protocol_process. While mostly
// incoming streaming g-code blocks, this also executes Grbl internal commands, such as
// settings, initiating the homing cycle, and toggling switch states. This differs from
// the realtime command module by being susceptible to when Grbl is ready to execute the
// next line during a cycle, so for switches like block delete, the switch only effects
// the lines that are processed afterward, not necessarily real-time during a cycle,
// since there are motions already stored in the buffer. However, this 'lag' should not
// be an issue, since these commands are not typically used during a cycle.
uint8_t system_execute_line(char *line)
{
uint8_t char_counter = 1;
uint8_t helper_var = 0; // Helper variable
float parameter, value;
switch( line[char_counter] ) {
case 0 : report_grbl_help(); break;
case '$': case 'G': case 'C': case 'X':
if ( line[(char_counter+1)] != 0 ) { return(STATUS_INVALID_STATEMENT); }
switch( line[char_counter] ) {
case '$' : // Prints Grbl settings
if ( sys.state & (STATE_CYCLE | STATE_HOLD) ) { return(STATUS_IDLE_ERROR); } // Block during cycle. Takes too long to print.
else { report_grbl_settings(); }
break;
case 'G' : // Prints gcode parser state
// TODO: Move this to realtime commands for GUIs to request this data during suspend-state.
report_gcode_modes();
break;
case 'C' : // Set check g-code mode [IDLE/CHECK]
// Perform reset when toggling off. Check g-code mode should only work if Grbl
// is idle and ready, regardless of alarm locks. This is mainly to keep things
// simple and consistent.
if ( sys.state == STATE_CHECK_MODE ) {
mc_reset();
report_feedback_message(MESSAGE_DISABLED);
} else {
if (sys.state) { return(STATUS_IDLE_ERROR); } // Requires no alarm mode.
sys.state = STATE_CHECK_MODE;
report_feedback_message(MESSAGE_ENABLED);
}
break;
case 'X' : // Disable alarm lock [ALARM]
if (sys.state == STATE_ALARM) {
report_feedback_message(MESSAGE_ALARM_UNLOCK);
sys.state = STATE_IDLE;
// Don't run startup script. Prevents stored moves in startup from causing accidents.
if (system_check_safety_door_ajar()) { // Check safety door switch before returning.
bit_true(sys.rt_exec_state, EXEC_SAFETY_DOOR);
protocol_execute_realtime(); // Enter safety door mode.
}
} // Otherwise, no effect.
break;
// case 'J' : break; // Jogging methods
// TODO: Here jogging can be placed for execution as a seperate subprogram. It does not need to be
// susceptible to other realtime commands except for e-stop. The jogging function is intended to
// be a basic toggle on/off with controlled acceleration and deceleration to prevent skipped
// steps. The user would supply the desired feedrate, axis to move, and direction. Toggle on would
// start motion and toggle off would initiate a deceleration to stop. One could 'feather' the
// motion by repeatedly toggling to slow the motion to the desired location. Location data would
// need to be updated real-time and supplied to the user through status queries.
// More controlled exact motions can be taken care of by inputting G0 or G1 commands, which are
// handled by the planner. It would be possible for the jog subprogram to insert blocks into the
// block buffer without having the planner plan them. It would need to manage de/ac-celerations
// on its own carefully. This approach could be effective and possibly size/memory efficient.
// }
// break;
}
break;
default :
// Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing)
if ( !(sys.state == STATE_IDLE || sys.state == STATE_ALARM) ) { return(STATUS_IDLE_ERROR); }
switch( line[char_counter] ) {
case '#' : // Print Grbl NGC parameters
if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
else { report_ngc_parameters(); }
break;
case 'H' : // Perform homing cycle [IDLE/ALARM]
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
sys.state = STATE_HOMING; // Set system state variable
// Only perform homing if Grbl is idle or lost.
// TODO: Likely not required.
if (system_check_safety_door_ajar()) { // Check safety door switch before homing.
bit_true(sys.rt_exec_state, EXEC_SAFETY_DOOR);
protocol_execute_realtime(); // Enter safety door mode.
}
mc_homing_cycle();
if (!sys.abort) { // Execute startup scripts after successful homing.
sys.state = STATE_IDLE; // Set to IDLE when complete.
st_go_idle(); // Set steppers to the settings idle state before returning.
system_execute_startup(line);
}
} else { return(STATUS_SETTING_DISABLED); }
break;
case 'I' : // Print or store build info. [IDLE/ALARM]
if ( line[++char_counter] == 0 ) {
settings_read_build_info(line);
report_build_info(line);
} else { // Store startup line [IDLE/ALARM]
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
helper_var = char_counter; // Set helper variable as counter to start of user info line.
do {
line[char_counter-helper_var] = line[char_counter];
} while (line[char_counter++] != 0);
settings_store_build_info(line);
}
break;
case 'N' : // Startup lines. [IDLE/ALARM]
if ( line[++char_counter] == 0 ) { // Print startup lines
for (helper_var=0; helper_var < N_STARTUP_LINE; helper_var++) {
if (!(settings_read_startup_line(helper_var, line))) {
report_status_message(STATUS_SETTING_READ_FAIL);
} else {
report_startup_line(helper_var,line);
}
}
break;
} else { // Store startup line [IDLE Only] Prevents motion during ALARM.
if (sys.state != STATE_IDLE) { return(STATUS_IDLE_ERROR); } // Store only when idle.
helper_var = true; // Set helper_var to flag storing method.
// No break. Continues into default: to read remaining command characters.
}
default : // Storing setting methods [IDLE/ALARM]
if(!read_float(line, &char_counter, &parameter)) { return(STATUS_BAD_NUMBER_FORMAT); }
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
if (helper_var) { // Store startup line
// Prepare sending gcode block to gcode parser by shifting all characters
helper_var = char_counter; // Set helper variable as counter to start of gcode block
do {
line[char_counter-helper_var] = line[char_counter];
} while (line[char_counter++] != 0);
// Execute gcode block to ensure block is valid.
helper_var = gc_execute_line(line); // Set helper_var to returned status code.
if (helper_var) { return(helper_var); }
else {
helper_var = trunc(parameter); // Set helper_var to int value of parameter
settings_store_startup_line(helper_var,line);
}
} else { // Store global setting.
if(!read_float(line, &char_counter, &value)) { return(STATUS_BAD_NUMBER_FORMAT); }
if((line[char_counter] != 0) || (parameter > 255)) { return(STATUS_INVALID_STATEMENT); }
return(settings_store_global_setting((uint8_t)parameter, value));
}
}
}
return(STATUS_OK); // If '$' command makes it to here, then everything's ok.
}
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
// NOTE: If motor steps and machine position are not in the same coordinate frame, this function
// serves as a central place to compute the transformation.
float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx)
{
float pos;
#ifdef COREXY
if (idx==A_MOTOR) {
pos = 0.5*((steps[A_MOTOR] + steps[B_MOTOR])/settings.steps_per_mm[idx]);
} else { // (idx==B_MOTOR)
pos = 0.5*((steps[A_MOTOR] - steps[B_MOTOR])/settings.steps_per_mm[idx]);
}
#else
pos = steps[idx]/settings.steps_per_mm[idx];
#endif
return(pos);
}
void system_convert_array_steps_to_mpos(float *position, int32_t *steps)
{
uint8_t idx;
for (idx=0; idx<N_AXIS; idx++) {
position[idx] = system_convert_axis_steps_to_mpos(steps, idx);
}
return;
}

108
grbl/system.h Normal file
View File

@ -0,0 +1,108 @@
/*
system.h - Header for system level commands and real-time processes
Part of Grbl
Copyright (c) 2014-2015 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef system_h
#define system_h
#include "grbl.h"
// Define system executor bit map. Used internally by realtime protocol as realtime command flags,
// which notifies the main program to execute the specified realtime command asynchronously.
// NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default
// flags are always false, so the realtime protocol only needs to check for a non-zero value to
// know when there is a realtime command to execute.
#define EXEC_STATUS_REPORT bit(0) // bitmask 00000001
#define EXEC_CYCLE_START bit(1) // bitmask 00000010
#define EXEC_CYCLE_STOP bit(2) // bitmask 00000100
#define EXEC_FEED_HOLD bit(3) // bitmask 00001000
#define EXEC_RESET bit(4) // bitmask 00010000
#define EXEC_SAFETY_DOOR bit(5) // bitmask 00100000
#define EXEC_MOTION_CANCEL bit(6) // bitmask 01000000
// Alarm executor bit map.
// NOTE: EXEC_CRITICAL_EVENT is an optional flag that must be set with an alarm flag. When enabled,
// this halts Grbl into an infinite loop until the user aknowledges the problem and issues a soft-
// reset command. For example, a hard limit event needs this type of halt and aknowledgement.
#define EXEC_CRITICAL_EVENT bit(0) // bitmask 00000001 (SPECIAL FLAG. See NOTE:)
#define EXEC_ALARM_HARD_LIMIT bit(1) // bitmask 00000010
#define EXEC_ALARM_SOFT_LIMIT bit(2) // bitmask 00000100
#define EXEC_ALARM_ABORT_CYCLE bit(3) // bitmask 00001000
#define EXEC_ALARM_PROBE_FAIL bit(4) // bitmask 00010000
#define EXEC_ALARM_HOMING_FAIL bit(5) // bitmask 00100000
// Define system state bit map. The state variable primarily tracks the individual functions
// of Grbl to manage each without overlapping. It is also used as a messaging flag for
// critical events.
#define STATE_IDLE 0 // Must be zero. No flags.
#define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access.
#define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only.
#define STATE_HOMING bit(2) // Performing homing cycle
#define STATE_CYCLE bit(3) // Cycle is running or motions are being executed.
#define STATE_HOLD bit(4) // Active feed hold
#define STATE_SAFETY_DOOR bit(5) // Safety door is ajar. Feed holds and de-energizes system.
#define STATE_MOTION_CANCEL bit(6) // Motion cancel by feed hold and return to idle.
// Define system suspend states.
#define SUSPEND_DISABLE 0 // Must be zero.
#define SUSPEND_ENABLE_HOLD bit(0) // Enabled. Indicates the cycle is active and currently undergoing a hold.
#define SUSPEND_ENABLE_READY bit(1) // Ready to resume with a cycle start command.
#define SUSPEND_ENERGIZE bit(2) // Re-energizes output before resume.
#define SUSPEND_MOTION_CANCEL bit(3) // Cancels resume motion. Used by probing routine.
// Define global system variables
typedef struct {
uint8_t abort; // System abort flag. Forces exit back to main loop for reset.
uint8_t state; // Tracks the current state of Grbl.
uint8_t suspend; // System suspend flag. Allows only realtime commands. Used primarily for holds.
volatile uint8_t rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks.
volatile uint8_t rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
int32_t position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
// NOTE: This may need to be a volatile variable, if problems arise.
uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR.
volatile uint8_t probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
int32_t probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
uint8_t probe_succeeded; // Tracks if last probing cycle was successful.
} system_t;
extern system_t sys;
// Initialize the serial protocol
void system_init();
// Returns if safety door is open or closed, based on pin state.
uint8_t system_check_safety_door_ajar();
// Executes an internal system command, defined as a string starting with a '$'
uint8_t system_execute_line(char *line);
// Execute the startup script lines stored in EEPROM upon initialization
void system_execute_startup(char *line);
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx);
// Updates a machine 'position' array based on the 'step' array sent.
void system_convert_array_steps_to_mpos(float *position, int32_t *steps);
#endif

View File

@ -1,306 +0,0 @@
/*
protocol.c - controls Grbl execution protocol and procedures
Part of Grbl v0.9
Copyright (c) 2012-2014 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
/*
This file is based on work from Grbl v0.8, distributed under the
terms of the MIT-license. See COPYING for more details.
Copyright (c) 2009-2011 Simen Svale Skogsrud
Copyright (c) 2011-2012 Sungeun K. Jeon
*/
#include "system.h"
#include "serial.h"
#include "settings.h"
#include "protocol.h"
#include "gcode.h"
#include "planner.h"
#include "stepper.h"
#include "motion_control.h"
#include "report.h"
static char line[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
// Directs and executes one line of formatted input from protocol_process. While mostly
// incoming streaming g-code blocks, this also directs and executes Grbl internal commands,
// such as settings, initiating the homing cycle, and toggling switch states.
static void protocol_execute_line(char *line)
{
protocol_execute_runtime(); // Runtime command check point.
if (sys.abort) { return; } // Bail to calling function upon system abort
if (line[0] == 0) {
// Empty or comment line. Send status message for syncing purposes.
report_status_message(STATUS_OK);
} else if (line[0] == '$') {
// Grbl '$' system command
report_status_message(system_execute_line(line));
} else if (sys.state == STATE_ALARM) {
// Everything else is gcode. Block if in alarm mode.
report_status_message(STATUS_ALARM_LOCK);
} else {
// Parse and execute g-code block!
report_status_message(gc_execute_line(line));
}
}
/*
GRBL PRIMARY LOOP:
*/
void protocol_main_loop()
{
// ------------------------------------------------------------
// Complete initialization procedures upon a power-up or reset.
// ------------------------------------------------------------
// Print welcome message
report_init_message();
// Check for and report alarm state after a reset, error, or an initial power up.
if (sys.state == STATE_ALARM) {
report_feedback_message(MESSAGE_ALARM_LOCK);
} else {
// All systems go!
sys.state = STATE_IDLE; // Set system to ready. Clear all state flags.
system_execute_startup(line); // Execute startup script.
}
// ---------------------------------------------------------------------------------
// Primary loop! Upon a system abort, this exits back to main() to reset the system.
// ---------------------------------------------------------------------------------
uint8_t iscomment = false;
uint8_t char_counter = 0;
uint8_t c;
for (;;) {
// Process one line of incoming serial data, as the data becomes available. Performs an
// initial filtering by removing spaces and comments and capitalizing all letters.
// NOTE: While comment, spaces, and block delete(if supported) handling should technically
// be done in the g-code parser, doing it here helps compress the incoming data into Grbl's
// line buffer, which is limited in size. The g-code standard actually states a line can't
// exceed 256 characters, but the Arduino Uno does not have the memory space for this.
// With a better processor, it would be very easy to pull this initial parsing out as a
// seperate task to be shared by the g-code parser and Grbl's system commands.
while((c = serial_read()) != SERIAL_NO_DATA) {
if ((c == '\n') || (c == '\r')) { // End of line reached
line[char_counter] = 0; // Set string termination character.
protocol_execute_line(line); // Line is complete. Execute it!
iscomment = false;
char_counter = 0;
} else {
if (iscomment) {
// Throw away all comment characters
if (c == ')') {
// End of comment. Resume line.
iscomment = false;
}
} else {
if (c <= ' ') {
// Throw away whitepace and control characters
} else if (c == '/') {
// Block delete NOT SUPPORTED. Ignore character.
// NOTE: If supported, would simply need to check the system if block delete is enabled.
} else if (c == '(') {
// Enable comments flag and ignore all characters until ')' or EOL.
// NOTE: This doesn't follow the NIST definition exactly, but is good enough for now.
// In the future, we could simply remove the items within the comments, but retain the
// comment control characters, so that the g-code parser can error-check it.
iscomment = true;
// } else if (c == ';') {
// Comment character to EOL NOT SUPPORTED. LinuxCNC definition. Not NIST.
// TODO: Install '%' feature
// } else if (c == '%') {
// Program start-end percent sign NOT SUPPORTED.
// NOTE: This maybe installed to tell Grbl when a program is running vs manual input,
// where, during a program, the system auto-cycle start will continue to execute
// everything until the next '%' sign. This will help fix resuming issues with certain
// functions that empty the planner buffer to execute its task on-time.
} else if (char_counter >= (LINE_BUFFER_SIZE-1)) {
// Detect line buffer overflow. Report error and reset line buffer.
report_status_message(STATUS_OVERFLOW);
iscomment = false;
char_counter = 0;
} else if (c >= 'a' && c <= 'z') { // Upcase lowercase
line[char_counter++] = c-'a'+'A';
} else {
line[char_counter++] = c;
}
}
}
}
// If there are no more characters in the serial read buffer to be processed and executed,
// this indicates that g-code streaming has either filled the planner buffer or has
// completed. In either case, auto-cycle start, if enabled, any queued moves.
protocol_auto_cycle_start();
protocol_execute_runtime(); // Runtime command check point.
if (sys.abort) { return; } // Bail to main() program loop to reset system.
}
return; /* Never reached */
}
// Executes run-time commands, when required. This is called from various check points in the main
// program, primarily where there may be a while loop waiting for a buffer to clear space or any
// point where the execution time from the last check point may be more than a fraction of a second.
// This is a way to execute runtime commands asynchronously (aka multitasking) with grbl's g-code
// parsing and planning functions. This function also serves as an interface for the interrupts to
// set the system runtime flags, where only the main program handles them, removing the need to
// define more computationally-expensive volatile variables. This also provides a controlled way to
// execute certain tasks without having two or more instances of the same task, such as the planner
// recalculating the buffer upon a feedhold or override.
// NOTE: The sys.execute variable flags are set by any process, step or serial interrupts, pinouts,
// limit switches, or the main program.
void protocol_execute_runtime()
{
uint8_t rt_exec = sys.execute; // Copy to avoid calling volatile multiple times
if (rt_exec) { // Enter only if any bit flag is true
// System alarm. Everything has shutdown by something that has gone severely wrong. Report
// the source of the error to the user. If critical, Grbl disables by entering an infinite
// loop until system reset/abort.
if (rt_exec & (EXEC_ALARM | EXEC_CRIT_EVENT)) {
sys.state = STATE_ALARM; // Set system alarm state
// Critical events. Hard/soft limit events identified by both critical event and alarm exec
// flags. Probe fail is identified by the critical event exec flag only.
if (rt_exec & EXEC_CRIT_EVENT) {
if (rt_exec & EXEC_ALARM) { report_alarm_message(ALARM_LIMIT_ERROR); }
else { report_alarm_message(ALARM_PROBE_FAIL); }
report_feedback_message(MESSAGE_CRITICAL_EVENT);
bit_false_atomic(sys.execute,EXEC_RESET); // Disable any existing reset
do {
// Nothing. Block EVERYTHING until user issues reset or power cycles. Hard limits
// typically occur while unattended or not paying attention. Gives the user time
// to do what is needed before resetting, like killing the incoming stream. The
// same could be said about soft limits. While the position is not lost, the incoming
// stream could be still engaged and cause a serious crash if it continues afterwards.
} while (bit_isfalse(sys.execute,EXEC_RESET));
// Standard alarm event. Only abort during motion qualifies.
} else {
// Runtime abort command issued during a cycle, feed hold, or homing cycle. Message the
// user that position may have been lost and set alarm state to enable the alarm lockout
// to indicate the possible severity of the problem.
report_alarm_message(ALARM_ABORT_CYCLE);
}
bit_false_atomic(sys.execute,(EXEC_ALARM | EXEC_CRIT_EVENT));
}
// Execute system abort.
if (rt_exec & EXEC_RESET) {
sys.abort = true; // Only place this is set true.
return; // Nothing else to do but exit.
}
// Execute and serial print status
if (rt_exec & EXEC_STATUS_REPORT) {
report_realtime_status();
bit_false_atomic(sys.execute,EXEC_STATUS_REPORT);
}
// Execute a feed hold with deceleration, only during cycle.
if (rt_exec & EXEC_FEED_HOLD) {
// !!! During a cycle, the segment buffer has just been reloaded and full. So the math involved
// with the feed hold should be fine for most, if not all, operational scenarios.
if (sys.state == STATE_CYCLE) {
sys.state = STATE_HOLD;
st_update_plan_block_parameters();
st_prep_buffer();
sys.auto_start = false; // Disable planner auto start upon feed hold.
}
bit_false_atomic(sys.execute,EXEC_FEED_HOLD);
}
// Execute a cycle start by starting the stepper interrupt begin executing the blocks in queue.
if (rt_exec & EXEC_CYCLE_START) {
if (sys.state == STATE_QUEUED) {
sys.state = STATE_CYCLE;
st_prep_buffer(); // Initialize step segment buffer before beginning cycle.
st_wake_up();
if (bit_istrue(settings.flags,BITFLAG_AUTO_START)) {
sys.auto_start = true; // Re-enable auto start after feed hold.
} else {
sys.auto_start = false; // Reset auto start per settings.
}
}
bit_false_atomic(sys.execute,EXEC_CYCLE_START);
}
// Reinitializes the cycle plan and stepper system after a feed hold for a resume. Called by
// runtime command execution in the main program, ensuring that the planner re-plans safely.
// NOTE: Bresenham algorithm variables are still maintained through both the planner and stepper
// cycle reinitializations. The stepper path should continue exactly as if nothing has happened.
// NOTE: EXEC_CYCLE_STOP is set by the stepper subsystem when a cycle or feed hold completes.
if (rt_exec & EXEC_CYCLE_STOP) {
if ( plan_get_current_block() ) { sys.state = STATE_QUEUED; }
else { sys.state = STATE_IDLE; }
bit_false_atomic(sys.execute,EXEC_CYCLE_STOP);
}
}
// Overrides flag byte (sys.override) and execution should be installed here, since they
// are runtime and require a direct and controlled interface to the main stepper program.
// Reload step segment buffer
if (sys.state & (STATE_CYCLE | STATE_HOLD | STATE_HOMING)) { st_prep_buffer(); }
}
// Block until all buffered steps are executed or in a cycle state. Works with feed hold
// during a synchronize call, if it should happen. Also, waits for clean cycle end.
void protocol_buffer_synchronize()
{
// If system is queued, ensure cycle resumes if the auto start flag is present.
protocol_auto_cycle_start();
// Check and set auto start to resume cycle after synchronize and caller completes.
if (sys.state == STATE_CYCLE) { sys.auto_start = true; }
while (plan_get_current_block() || (sys.state == STATE_CYCLE)) {
protocol_execute_runtime(); // Check and execute run-time commands
if (sys.abort) { return; } // Check for system abort
}
}
// Auto-cycle start has two purposes: 1. Resumes a plan_synchronize() call from a function that
// requires the planner buffer to empty (spindle enable, dwell, etc.) 2. As a user setting that
// automatically begins the cycle when a user enters a valid motion command manually. This is
// intended as a beginners feature to help new users to understand g-code. It can be disabled
// as a beginner tool, but (1.) still operates. If disabled, the operation of cycle start is
// manually issuing a cycle start command whenever the user is ready and there is a valid motion
// command in the planner queue.
// NOTE: This function is called from the main loop and mc_line() only and executes when one of
// two conditions exist respectively: There are no more blocks sent (i.e. streaming is finished,
// single commands), or the planner buffer is full and ready to go.
void protocol_auto_cycle_start() { if (sys.auto_start) { bit_true_atomic(sys.execute, EXEC_CYCLE_START); } }

199
system.c
View File

@ -1,199 +0,0 @@
/*
system.c - Handles system level commands and real-time processes
Part of Grbl v0.9
Copyright (c) 2014 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#include "system.h"
#include "settings.h"
#include "gcode.h"
#include "motion_control.h"
#include "report.h"
#include "print.h"
void system_init()
{
PINOUT_DDR &= ~(PINOUT_MASK); // Configure as input pins
PINOUT_PORT |= PINOUT_MASK; // Enable internal pull-up resistors. Normal high operation.
PINOUT_PCMSK |= PINOUT_MASK; // Enable specific pins of the Pin Change Interrupt
PCICR |= (1 << PINOUT_INT); // Enable Pin Change Interrupt
}
// Pin change interrupt for pin-out commands, i.e. cycle start, feed hold, and reset. Sets
// only the runtime command execute variable to have the main program execute these when
// its ready. This works exactly like the character-based runtime commands when picked off
// directly from the incoming serial data stream.
ISR(PINOUT_INT_vect)
{
// Enter only if any pinout pin is actively low.
if ((PINOUT_PIN & PINOUT_MASK) ^ PINOUT_MASK) {
if (bit_isfalse(PINOUT_PIN,bit(PIN_RESET))) {
mc_reset();
} else if (bit_isfalse(PINOUT_PIN,bit(PIN_FEED_HOLD))) {
bit_true(sys.execute, EXEC_FEED_HOLD);
} else if (bit_isfalse(PINOUT_PIN,bit(PIN_CYCLE_START))) {
bit_true(sys.execute, EXEC_CYCLE_START);
}
}
}
// Executes user startup script, if stored.
void system_execute_startup(char *line)
{
uint8_t n;
for (n=0; n < N_STARTUP_LINE; n++) {
if (!(settings_read_startup_line(n, line))) {
report_status_message(STATUS_SETTING_READ_FAIL);
} else {
if (line[0] != 0) {
printString(line); // Echo startup line to indicate execution.
report_status_message(gc_execute_line(line));
}
}
}
}
// Directs and executes one line of formatted input from protocol_process. While mostly
// incoming streaming g-code blocks, this also executes Grbl internal commands, such as
// settings, initiating the homing cycle, and toggling switch states. This differs from
// the runtime command module by being susceptible to when Grbl is ready to execute the
// next line during a cycle, so for switches like block delete, the switch only effects
// the lines that are processed afterward, not necessarily real-time during a cycle,
// since there are motions already stored in the buffer. However, this 'lag' should not
// be an issue, since these commands are not typically used during a cycle.
uint8_t system_execute_line(char *line)
{
uint8_t char_counter = 1;
uint8_t helper_var = 0; // Helper variable
float parameter, value;
switch( line[char_counter] ) {
case 0 : report_grbl_help(); break;
case '$' : // Prints Grbl settings
if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
if ( sys.state & (STATE_CYCLE | STATE_HOLD) ) { return(STATUS_IDLE_ERROR); } // Block during cycle. Takes too long to print.
else { report_grbl_settings(); }
break;
case 'G' : // Prints gcode parser state
if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
else { report_gcode_modes(); }
break;
case 'C' : // Set check g-code mode [IDLE/CHECK]
if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
// Perform reset when toggling off. Check g-code mode should only work if Grbl
// is idle and ready, regardless of alarm locks. This is mainly to keep things
// simple and consistent.
if ( sys.state == STATE_CHECK_MODE ) {
mc_reset();
report_feedback_message(MESSAGE_DISABLED);
} else {
if (sys.state) { return(STATUS_IDLE_ERROR); } // Requires no alarm mode.
sys.state = STATE_CHECK_MODE;
report_feedback_message(MESSAGE_ENABLED);
}
break;
case 'X' : // Disable alarm lock [ALARM]
if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
if (sys.state == STATE_ALARM) {
report_feedback_message(MESSAGE_ALARM_UNLOCK);
sys.state = STATE_IDLE;
// Don't run startup script. Prevents stored moves in startup from causing accidents.
} // Otherwise, no effect.
break;
// case 'J' : break; // Jogging methods
// TODO: Here jogging can be placed for execution as a seperate subprogram. It does not need to be
// susceptible to other runtime commands except for e-stop. The jogging function is intended to
// be a basic toggle on/off with controlled acceleration and deceleration to prevent skipped
// steps. The user would supply the desired feedrate, axis to move, and direction. Toggle on would
// start motion and toggle off would initiate a deceleration to stop. One could 'feather' the
// motion by repeatedly toggling to slow the motion to the desired location. Location data would
// need to be updated real-time and supplied to the user through status queries.
// More controlled exact motions can be taken care of by inputting G0 or G1 commands, which are
// handled by the planner. It would be possible for the jog subprogram to insert blocks into the
// block buffer without having the planner plan them. It would need to manage de/ac-celerations
// on its own carefully. This approach could be effective and possibly size/memory efficient.
default :
// Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing)
if ( !(sys.state == STATE_IDLE || sys.state == STATE_ALARM) ) { return(STATUS_IDLE_ERROR); }
switch( line[char_counter] ) {
case '#' : // Print Grbl NGC parameters
if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
else { report_ngc_parameters(); }
break;
case 'H' : // Perform homing cycle [IDLE/ALARM]
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
// Only perform homing if Grbl is idle or lost.
mc_homing_cycle();
if (!sys.abort) { system_execute_startup(line); } // Execute startup scripts after successful homing.
} else { return(STATUS_SETTING_DISABLED); }
break;
case 'I' : // Print or store build info. [IDLE/ALARM]
if ( line[++char_counter] == 0 ) {
settings_read_build_info(line);
report_build_info(line);
} else { // Store startup line [IDLE/ALARM]
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
helper_var = char_counter; // Set helper variable as counter to start of user info line.
do {
line[char_counter-helper_var] = line[char_counter];
} while (line[char_counter++] != 0);
settings_store_build_info(line);
}
break;
case 'N' : // Startup lines. [IDLE/ALARM]
if ( line[++char_counter] == 0 ) { // Print startup lines
for (helper_var=0; helper_var < N_STARTUP_LINE; helper_var++) {
if (!(settings_read_startup_line(helper_var, line))) {
report_status_message(STATUS_SETTING_READ_FAIL);
} else {
report_startup_line(helper_var,line);
}
}
break;
} else { // Store startup line [IDLE Only] Prevents motion during ALARM.
if (sys.state != STATE_IDLE) { return(STATUS_IDLE_ERROR); } // Store only when idle.
helper_var = true; // Set helper_var to flag storing method.
// No break. Continues into default: to read remaining command characters.
}
default : // Storing setting methods [IDLE/ALARM]
if(!read_float(line, &char_counter, &parameter)) { return(STATUS_BAD_NUMBER_FORMAT); }
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
if (helper_var) { // Store startup line
// Prepare sending gcode block to gcode parser by shifting all characters
helper_var = char_counter; // Set helper variable as counter to start of gcode block
do {
line[char_counter-helper_var] = line[char_counter];
} while (line[char_counter++] != 0);
// Execute gcode block to ensure block is valid.
helper_var = gc_execute_line(line); // Set helper_var to returned status code.
if (helper_var) { return(helper_var); }
else {
helper_var = trunc(parameter); // Set helper_var to int value of parameter
settings_store_startup_line(helper_var,line);
}
} else { // Store global setting.
if(!read_float(line, &char_counter, &value)) { return(STATUS_BAD_NUMBER_FORMAT); }
if(line[char_counter] != 0) { return(STATUS_INVALID_STATEMENT); }
return(settings_store_global_setting((uint8_t)parameter, value));
}
}
}
return(STATUS_OK); // If '$' command makes it to here, then everything's ok.
}

View File

@ -1,98 +0,0 @@
/*
system.h - Header for system level commands and real-time processes
Part of Grbl v0.9
Copyright (c) 2014 Sungeun K. Jeon
Grbl is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
Grbl is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef system_h
#define system_h
// Define system header files and standard libraries used by Grbl
#include <avr/io.h>
#include <avr/pgmspace.h>
#include <avr/interrupt.h>
#include <avr/wdt.h>
#include <util/delay.h>
#include <math.h>
#include <inttypes.h>
#include <string.h>
#include <stdlib.h>
#include <stdint.h>
#include <stdbool.h>
// Define Grbl configuration and shared header files
#include "config.h"
#include "defaults.h"
#include "cpu_map.h"
#include "nuts_bolts.h"
// Define system executor bit map. Used internally by runtime protocol as runtime command flags,
// which notifies the main program to execute the specified runtime command asynchronously.
// NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default
// flags are always false, so the runtime protocol only needs to check for a non-zero value to
// know when there is a runtime command to execute.
#define EXEC_STATUS_REPORT bit(0) // bitmask 00000001
#define EXEC_CYCLE_START bit(1) // bitmask 00000010
#define EXEC_CYCLE_STOP bit(2) // bitmask 00000100
#define EXEC_FEED_HOLD bit(3) // bitmask 00001000
#define EXEC_RESET bit(4) // bitmask 00010000
#define EXEC_ALARM bit(5) // bitmask 00100000
#define EXEC_CRIT_EVENT bit(6) // bitmask 01000000
// #define bit(7) // bitmask 10000000
// Define system state bit map. The state variable primarily tracks the individual functions
// of Grbl to manage each without overlapping. It is also used as a messaging flag for
// critical events.
#define STATE_IDLE 0 // Must be zero. No flags.
#define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access.
#define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only.
#define STATE_HOMING bit(2) // Performing homing cycle
#define STATE_QUEUED bit(3) // Indicates buffered blocks, awaiting cycle start.
#define STATE_CYCLE bit(4) // Cycle is running
#define STATE_HOLD bit(5) // Executing feed hold
// #define STATE_JOG bit(6) // Jogging mode is unique like homing.
// Define global system variables
typedef struct {
uint8_t abort; // System abort flag. Forces exit back to main loop for reset.
uint8_t state; // Tracks the current state of Grbl.
volatile uint8_t execute; // Global system runtime executor bitflag variable. See EXEC bitmasks.
uint8_t homing_axis_lock;
int32_t position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
// NOTE: This may need to be a volatile variable, if problems arise.
uint8_t auto_start; // Planner auto-start flag. Toggled off during feed hold. Defaulted by settings.
volatile uint8_t probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
int32_t probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
} system_t;
extern system_t sys;
// Initialize the serial protocol
void system_init();
// Executes an internal system command, defined as a string starting with a '$'
uint8_t system_execute_line(char *line);
// Checks and executes a runtime command at various stop points in main program
void system_execute_runtime();
// Execute the startup script lines stored in EEPROM upon initialization
void system_execute_startup(char *line);
#endif

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -1,773 +0,0 @@
(ShapeOko2 "Hello World" test file)
(Set up sheet of paper landscape, long edge on X-axis)
(Starting location around the lower[-y] left[-x] corner)
(originally Generated by PartKam Version 0.05)
G20 G90 (remove G40)
(write the words)
G0 Z0.125
(remove x)
G17
G0 X0.435 Y0.4042
G1 Z-0.01 F10
G3 X0.4557 Y0.4046 I0 J0.4533 F40
G3 X0.4728 Y0.4059 I-0.0142 J0.3117
G3 X0.4898 Y0.4082 I-0.0257 J0.2542
G3 X0.5034 Y0.4111 I-0.028 J0.1653
G3 X0.5168 Y0.415 I-0.0472 J0.1844
G3 X0.5278 Y0.4192 I-0.0435 J0.1296
G3 X0.5383 Y0.4245 I-0.0462 J0.1062
G3 X0.5468 Y0.4299 I-0.0415 J0.0739
G3 X0.5545 Y0.4363 I-0.0474 J0.0649
G3 X0.5606 Y0.4429 I-0.0441 J0.0468
G3 X0.5656 Y0.4503 I-0.0464 J0.0371
G3 X0.5694 Y0.4582 I-0.0481 J0.0278
G3 X0.5721 Y0.4664 I-0.0805 J0.031
G3 X0.5741 Y0.4754 I-0.093 J0.0254
G3 X0.5753 Y0.4846 I-0.1022 J0.0176
G3 X0.5757 Y0.4946 I-0.1224 J0.01
G3 X0.5731 Y0.5153 I-0.083 J0
G3 X0.5656 Y0.5337 I-0.0731 J-0.0188
G3 X0.5537 Y0.5498 I-0.072 J-0.0408
G3 X0.5355 Y0.5656 I-0.0876 J-0.083
G3 X0.5146 Y0.5784 I-0.1178 J-0.1676
G3 X0.4808 Y0.5949 I-0.2293 J-0.4268
G3 X0.4459 Y0.6092 I-0.282 J-0.6397
G3 X0.3973 Y0.6265 I-0.4624 J-1.2235
G2 X0.376 Y0.6343 I0.3353 J0.9488
G2 X0.3546 Y0.6427 I0.3684 J0.9724
G2 X0.3333 Y0.6515 I0.3967 J0.9808
G2 X0.3119 Y0.661 I0.4333 J1.0077
G2 X0.2909 Y0.6715 I0.1396 J0.3066
G2 X0.2714 Y0.683 I0.1507 J0.2779
G2 X0.2527 Y0.6959 I0.1666 J0.2606
G2 X0.2353 Y0.71 I0.1811 J0.2422
G2 X0.2191 Y0.7255 I0.1487 J0.1708
G2 X0.2045 Y0.7427 I0.1668 J0.1572
G2 X0.1916 Y0.7611 I0.1861 J0.1436
G2 X0.18 Y0.7816 I0.2168 J0.1363
G2 X0.1709 Y0.8032 I0.1508 J0.0765
G2 X0.164 Y0.8282 I0.1965 J0.0675
G2 X0.1601 Y0.854 I0.2316 J0.0483
G2 X0.1587 Y0.884 I0.3133 J0.03
G2 X0.1601 Y0.914 I0.3058 J0
G2 X0.1643 Y0.9413 I0.2576 J-0.0254
G2 X0.1715 Y0.968 I0.2377 J-0.0494
G2 X0.1813 Y0.9926 I0.2132 J-0.0704
G2 X0.1938 Y1.016 I0.2171 J-0.1015
G2 X0.2086 Y1.0374 I0.1951 J-0.1191
G2 X0.2257 Y1.0569 I0.1807 J-0.1407
G2 X0.2453 Y1.0749 I0.1727 J-0.1691
G2 X0.2668 Y1.0906 I0.1588 J-0.1942
G2 X0.2912 Y1.1049 I0.1534 J-0.2346
G2 X0.3168 Y1.1167 I0.1391 J-0.2681
G2 X0.3458 Y1.127 I0.1352 J-0.3335
G2 X0.3756 Y1.1348 I0.1068 J-0.3459
G2 X0.4086 Y1.1407 I0.0911 J-0.4184
G2 X0.442 Y1.144 I0.0638 J-0.4657
G2 X0.4789 Y1.1452 I0.037 J-0.5706
G2 X0.5228 Y1.144 I0 J-0.7643
G2 X0.5609 Y1.1405 I-0.0333 J-0.5787
G2 X0.5986 Y1.1344 I-0.062 J-0.5001
G2 X0.6309 Y1.1264 I-0.0758 J-0.3755
G2 X0.6627 Y1.1163 I-0.2335 J-0.7931
G2 X0.6893 Y1.1066 I-0.191 J-0.5638
G2 X0.7154 Y1.0955 I-0.1827 J-0.4653
G2 X0.7364 Y1.0849 I-0.1447 J-0.3148
G1 X0.6799 Y0.9304
G3 X0.6615 Y0.9394 I-0.2077 J-0.4011
G3 X0.6414 Y0.9482 I-0.2158 J-0.4675
G3 X0.621 Y0.9561 I-0.2093 J-0.5093
G3 X0.5989 Y0.9637 I-0.2164 J-0.5924
G3 X0.5764 Y0.9698 I-0.0747 J-0.2309
G3 X0.5498 Y0.9745 I-0.0698 J-0.3171
G3 X0.5228 Y0.9772 I-0.0502 J-0.3738
G3 X0.4915 Y0.9782 I-0.0314 J-0.5063
G3 X0.4565 Y0.9767 I0 J-0.4369
G3 X0.4311 Y0.9733 I0.0187 J-0.2329
G3 X0.4065 Y0.9666 I0.0312 J-0.1619
G3 X0.3904 Y0.9587 I0.0277 J-0.0771
G3 X0.3767 Y0.9474 I0.0374 J-0.0591
G3 X0.3673 Y0.9341 I0.0432 J-0.0405
G3 X0.3618 Y0.9186 I0.0563 J-0.029
G3 X0.3596 Y0.899 I0.0892 J-0.0196
G3 X0.3604 Y0.8872 I0.093 J0
G3 X0.3625 Y0.8771 I0.0704 J0.009
G3 X0.366 Y0.8674 I0.0617 J0.0173
G3 X0.3709 Y0.8588 I0.0525 J0.0244
G3 X0.377 Y0.851 I0.0702 J0.0485
G3 X0.3846 Y0.8433 I0.0772 J0.0678
G3 X0.3929 Y0.8363 I0.0778 J0.0845
G3 X0.403 Y0.8293 I0.0886 J0.1165
G3 X0.4135 Y0.823 I0.1229 J0.1933
G3 X0.4253 Y0.8168 I0.1326 J0.2355
G3 X0.4373 Y0.8111 I0.1314 J0.2629
G3 X0.4507 Y0.8055 I0.1413 J0.3181
G3 X0.4642 Y0.8002 I0.4349 J1.1
G3 X0.4791 Y0.7946 I0.5053 J1.3254
G3 X0.4941 Y0.7892 I0.5351 J1.4522
G3 X0.5104 Y0.7835 I0.615 J1.7234
G2 X0.5441 Y0.7706 I-0.62 J-1.6745
G2 X0.5738 Y0.7585 I-0.5126 J-1.3027
G2 X0.6031 Y0.7457 I-0.4768 J-1.135
G2 X0.6284 Y0.7339 I-0.3858 J-0.8553
G2 X0.653 Y0.7208 I-0.1756 J-0.3603
G2 X0.6744 Y0.7073 I-0.164 J-0.2844
G2 X0.6946 Y0.6922 I-0.1689 J-0.2468
G2 X0.7119 Y0.6767 I-0.1605 J-0.1966
G2 X0.7276 Y0.6596 I-0.1493 J-0.1521
G2 X0.741 Y0.6412 I-0.1581 J-0.1293
G2 X0.7522 Y0.6215 I-0.172 J-0.1113
G2 X0.7615 Y0.6001 I-0.1936 J-0.0968
G2 X0.7685 Y0.5778 I-0.2008 J-0.0746
G2 X0.7738 Y0.5514 I-0.2755 J-0.0693
G2 X0.7768 Y0.5247 I-0.3264 J-0.0499
G2 X0.7779 Y0.4934 I-0.4455 J-0.0313
G2 X0.772 Y0.4337 I-0.3082 J0
G2 X0.7565 Y0.3852 I-0.2183 J0.0431
G2 X0.7301 Y0.3418 I-0.1887 J0.0852
G2 X0.6925 Y0.3043 I-0.1784 J0.1413
G2 X0.647 Y0.2762 I-0.146 J0.1856
G2 X0.5854 Y0.2539 I-0.1514 J0.3216
G2 X0.5204 Y0.2419 I-0.1159 J0.4443
G2 X0.435 Y0.2371 I-0.0854 J0.7648
G2 X0.4061 Y0.2376 I0 J0.919
G2 X0.38 Y0.2388 I0.0236 J0.75
G2 X0.354 Y0.2411 I0.0448 J0.6746
G2 X0.3307 Y0.244 I0.0572 J0.5433
G2 X0.3075 Y0.2478 I0.1319 J0.886
G2 X0.2869 Y0.2517 I0.1238 J0.7045
G2 X0.2664 Y0.2563 I0.1284 J0.6229
G2 X0.2485 Y0.261 I0.1166 J0.4841
G2 X0.2307 Y0.2663 I0.1781 J0.6347
G2 X0.2152 Y0.2714 I0.1505 J0.4834
G2 X0.1999 Y0.277 I0.1443 J0.4161
G2 X0.1869 Y0.2823 I0.1191 J0.3062
G2 X0.1741 Y0.2881 I0.2781 J0.6336
G2 X0.1632 Y0.2933 I0.2146 J0.4632
G2 X0.1524 Y0.2988 I0.1915 J0.3889
G2 X0.1436 Y0.3037 I0.1422 J0.2695
G1 X0.1988 Y0.4594
G3 X0.2186 Y0.4494 I0.1622 J0.2959
G3 X0.2423 Y0.4392 I0.1933 J0.4152
G3 X0.2666 Y0.4302 I0.1967 J0.4934
G3 X0.2949 Y0.4211 I0.2292 J0.6675
G3 X0.3238 Y0.414 I0.0929 J0.313
G3 X0.3585 Y0.4084 I0.0897 J0.4486
G3 X0.3936 Y0.4053 I0.065 J0.537
G3 X0.435 Y0.4042 I0.0414 J0.7464
G0 Z0.125
G0 X1.4536 Y1.1251
G1 Z-0.01 F10
G1 X1.6496 Y1.1251 F40
G1 X1.6496 Y0.2547
G1 X1.4536 Y0.2547
G1 X1.4536 Y0.624
G1 X1.1246 Y0.624
G1 X1.1246 Y0.2547
G1 X0.9286 Y0.2547
G1 X0.9286 Y1.1251
G1 X1.1246 Y1.1251
G1 X1.1246 Y0.7923
G1 X1.4536 Y0.7923
G1 X1.4536 Y1.1251
G0 Z0.125
G0 X2.4338 Y0.2547
G1 Z-0.01 F10
G1 X2.403 Y0.3477 F40
G1 X2.3698 Y0.4431
G1 X2.0306 Y0.4431
G1 X1.9973 Y0.3477
G1 X1.9666 Y0.2547
G1 X1.7631 Y0.2547
G2 X1.7877 Y0.325 I17.8599 J-6.2193
G2 X1.8108 Y0.39 I15.3154 J-5.401
G2 X1.8342 Y0.455 I14.1288 J-5.0502
G2 X1.856 Y0.5147 I11.9637 J-4.3385
G2 X1.8782 Y0.5743 I9.7422 J-3.588
G2 X1.8995 Y0.6306 I8.7097 J-3.2684
G2 X1.9212 Y0.6867 I8.2125 J-3.1426
G2 X1.9421 Y0.7395 I7.2956 J-2.8491
G2 X1.9633 Y0.7922 I8.4224 J-3.3598
G2 X1.9838 Y0.8424 I7.6529 J-3.1085
G2 X2.0047 Y0.8924 I7.277 J-3.0116
G2 X2.025 Y0.9399 I6.5821 J-2.7772
G2 X2.0457 Y0.9872 I4.2002 J-1.8081
G2 X2.0666 Y1.0336 I4.0692 J-1.8064
G2 X2.0881 Y1.0798 I3.9952 J-1.8286
G2 X2.1098 Y1.1251 I3.8717 J-1.8266
G1 X2.2969 Y1.1251
G2 X2.3181 Y1.0798 I-6.0675 J-2.8652
G2 X2.3393 Y1.0336 I-6.3027 J-2.919
G2 X2.3602 Y0.9872 I-6.4339 J-2.9227
G2 X2.381 Y0.9399 I-6.6806 J-2.977
G2 X2.4016 Y0.8924 I-5.4185 J-2.3686
G2 X2.4227 Y0.8424 I-5.9798 J-2.5519
G2 X2.4433 Y0.7922 I-6.2861 J-2.6208
G2 X2.4646 Y0.7395 I-6.9077 J-2.8155
G2 X2.4854 Y0.6867 I-7.3628 J-2.9356
G2 X2.5071 Y0.6306 I-8.2907 J-3.237
G2 X2.5284 Y0.5743 I-8.7947 J-3.3654
G2 X2.5506 Y0.5147 I-9.8397 J-3.6933
G2 X2.5724 Y0.455 I-11.8601 J-4.3698
G2 X2.5958 Y0.39 I-14.0105 J-5.0822
G2 X2.6189 Y0.325 I-15.1905 J-5.4307
G2 X2.6436 Y0.2547 I-17.7191 J-6.2494
G1 X2.4338 Y0.2547
G0 Z0.125
G0 X2.1989 Y0.9279
G1 Z-0.01 F10
G2 X2.1957 Y0.9185 I-0.5641 J0.1881 F40
G2 X2.1911 Y0.9056 I-1.0677 J0.3759
G2 X2.1863 Y0.8928 I-1.4028 J0.513
G2 X2.1801 Y0.8764 I-2.2751 J0.8558
G3 X2.1738 Y0.8601 I30.9994 J-11.916
G3 X2.1666 Y0.8413 I41.2401 J-15.8275
G3 X2.1594 Y0.8224 I47.1201 J-18.0595
G3 X2.1512 Y0.8011 I60.4881 J-23.1553
G3 X2.143 Y0.7797 I19.8859 J-7.6046
G3 X2.1341 Y0.7562 I24.1414 J-9.2022
G3 X2.1251 Y0.7326 I26.4832 J-10.0653
G3 X2.1154 Y0.7069 I31.5951 J-11.976
G3 X2.1057 Y0.6811 I4.794 J-1.8127
G3 X2.0958 Y0.6541 I5.244 J-1.9507
G3 X2.086 Y0.6271 I5.4846 J-2.0082
G3 X2.0758 Y0.5988 I5.9771 J-2.1552
G1 X2.3233 Y0.5988
G3 X2.3132 Y0.6271 I-12.9639 J-4.6057
G3 X2.3035 Y0.6541 I-11.8652 J-4.2445
G3 X2.2937 Y0.6811 I-11.3354 J-4.0841
G3 X2.2843 Y0.7069 I-10.3324 J-3.7506
G3 X2.2748 Y0.7326 I-4.3139 J-1.5783
G3 X2.266 Y0.7562 I-3.6331 J-1.3538
G3 X2.2569 Y0.7797 I-3.3175 J-1.2608
G3 X2.2485 Y0.8011 I-2.7503 J-1.0677
G2 X2.2401 Y0.8224 I9.4214 J3.7426
G2 X2.2327 Y0.8413 I7.3257 J2.8909
G2 X2.2253 Y0.8601 I6.4077 J2.5096
G2 X2.219 Y0.8764 I4.802 J1.8645
G3 X2.2127 Y0.8927 I-7.2811 J-2.7989
G3 X2.2077 Y0.9056 I-4.551 J-1.7612
G3 X2.2027 Y0.9185 I-3.4837 J-1.3595
G3 X2.1989 Y0.9279 I-1.8801 J-0.7417
G0 Z0.125
G0 X3.0175 Y1.1352
G1 Z-0.01 F10
G2 X3.1143 Y1.1304 I0 J-0.9783 F40
G2 X3.1895 Y1.118 I-0.06 J-0.603
G2 X3.2619 Y1.0953 I-0.1063 J-0.4642
G2 X3.3164 Y1.0667 I-0.1178 J-0.2911
G2 X3.362 Y1.0268 I-0.1208 J-0.184
G2 X3.3946 Y0.9764 I-0.1634 J-0.1415
G2 X3.4133 Y0.9188 I-0.2268 J-0.1055
G2 X3.4207 Y0.8425 I-0.3919 J-0.0763
G2 X3.4132 Y0.7656 I-0.4013 J0
G2 X3.3943 Y0.7073 I-0.2484 J0.0485
G2 X3.3613 Y0.6563 I-0.1992 J0.0927
G2 X3.3152 Y0.6158 I-0.1701 J0.147
G2 X3.26 Y0.5867 I-0.1755 J0.2656
G2 X3.187 Y0.5635 I-0.1806 J0.4426
G2 X3.1111 Y0.551 I-0.1365 J0.5905
G2 X3.0137 Y0.5461 I-0.0974 J0.969
G1 X2.9522 Y0.5461
G1 X2.9522 Y0.2547
G1 X2.7562 Y0.2547
G1 X2.7562 Y1.1126
G2 X2.7883 Y1.1183 I0.19 J-0.9718
G2 X2.8222 Y1.1232 I0.1732 J-1.0725
G2 X2.8561 Y1.1271 I0.1462 J-1.1296
G2 X2.8919 Y1.1301 I0.1235 J-1.2476
G2 X2.9277 Y1.1324 I0.1789 J-2.5504
G2 X2.9591 Y1.1339 I0.1097 J-1.9581
G2 X2.9905 Y1.1349 I0.068 J-1.701
G2 X3.0175 Y1.1352 I0.027 J-1.257
G0 Z0.125
G0 X3.03 Y0.9681
G1 Z-0.01 F10
G1 X2.988 Y0.9669 F40
G3 X2.9775 Y0.9662 I0.1375 J-2.2842
G3 X2.9686 Y0.9656 I0.1084 J-1.6742
G3 X2.9597 Y0.965 I0.0994 J-1.4177
G3 X2.9522 Y0.9644 I0.0758 J-0.9911
G1 X2.9522 Y0.7131
G1 X3.0137 Y0.7131
G3 X3.0644 Y0.7151 I0 J0.6562
G3 X3.1029 Y0.72 I-0.0297 J0.3827
G3 X3.1403 Y0.7294 I-0.051 J0.2826
G3 X3.1669 Y0.7408 I-0.0497 J0.1535
G3 X3.1895 Y0.7577 I-0.0439 J0.0818
G3 X3.2056 Y0.7803 I-0.0644 J0.0629
G3 X3.2147 Y0.807 I-0.0959 J0.048
G3 X3.2184 Y0.8438 I-0.1813 J0.0368
G3 X3.2175 Y0.8619 I-0.1838 J0
G3 X3.2151 Y0.877 I-0.1312 J-0.013
G3 X3.2109 Y0.8918 I-0.1104 J-0.0241
G3 X3.2052 Y0.9041 I-0.0828 J-0.0303
G3 X3.1979 Y0.9154 I-0.0877 J-0.0485
G3 X3.1892 Y0.9256 I-0.078 J-0.058
G3 X3.1793 Y0.9344 I-0.0709 J-0.0697
G3 X3.1676 Y0.9424 I-0.0682 J-0.088
G3 X3.155 Y0.9489 I-0.0659 J-0.1118
G3 X3.1404 Y0.9546 I-0.0654 J-0.1451
G3 X3.1253 Y0.959 I-0.0571 J-0.1695
G3 X3.1079 Y0.9625 I-0.0538 J-0.2228
G3 X3.0903 Y0.9649 I-0.0622 J-0.3868
G3 X3.0709 Y0.9667 I-0.0535 J-0.4675
G3 X3.0514 Y0.9677 I-0.0373 J-0.514
G3 X3.03 Y0.9681 I-0.0213 J-0.6163
G0 Z0.125
G0 X3.5657 Y0.2547
G1 Z-0.01 F10
G1 X3.5657 Y1.1251 F40
G1 X4.1536 Y1.1251
G1 X4.1536 Y0.9606
G1 X3.7617 Y0.9606
G1 X3.7617 Y0.7898
G1 X4.1096 Y0.7898
G1 X4.1096 Y0.629
G1 X3.7617 Y0.629
G1 X3.7617 Y0.4193
G1 X4.1825 Y0.4193
G1 X4.1825 Y0.2547
G1 X3.5657 Y0.2547
G0 Z0.125
G0 X4.4908 Y0.6905
G1 Z-0.01 F10
G3 X4.4918 Y0.6586 I0.4971 J0 F40
G3 X4.4947 Y0.6296 I0.4109 J0.0265
G3 X4.4997 Y0.601 I0.3733 J0.0507
G3 X4.5065 Y0.575 I0.3139 J0.0676
G3 X4.5154 Y0.5497 I0.3036 J0.0925
G3 X4.5256 Y0.5271 I0.2511 J0.1004
G3 X4.5379 Y0.5056 I0.2254 J0.1151
G3 X4.5517 Y0.4864 I0.1934 J0.124
G3 X4.5674 Y0.4689 I0.1636 J0.1303
G3 X4.5845 Y0.4536 I0.1398 J0.1398
G3 X4.6033 Y0.4405 I0.1224 J0.1548
G3 X4.6239 Y0.4293 I0.109 J0.1765
G3 X4.6457 Y0.4206 I0.0819 J0.174
G3 X4.6698 Y0.4142 I0.0674 J0.205
G3 X4.6944 Y0.4105 I0.0471 J0.2296
G3 X4.7219 Y0.4092 I0.0275 J0.2849
G3 X4.7487 Y0.4105 I0 J0.2758
G3 X4.7732 Y0.4142 I-0.0227 J0.2323
G3 X4.7971 Y0.4206 I-0.0443 J0.2143
G3 X4.8192 Y0.4293 I-0.0629 J0.192
G3 X4.8402 Y0.4405 I-0.0881 J0.1899
G3 X4.8591 Y0.4536 I-0.1024 J0.1678
G3 X4.8763 Y0.4689 I-0.1208 J0.154
G3 X4.8921 Y0.4864 I-0.1445 J0.1452
G3 X4.9058 Y0.5056 I-0.1798 J0.1433
G3 X4.9181 Y0.5271 I-0.2133 J0.1367
G3 X4.9284 Y0.5497 I-0.2412 J0.1232
G3 X4.9373 Y0.575 I-0.295 J0.1181
G3 X4.944 Y0.601 I-0.3069 J0.0937
G3 X4.9491 Y0.6296 I-0.3679 J0.0794
G3 X4.952 Y0.6586 I-0.4076 J0.0554
G3 X4.953 Y0.6905 I-0.4955 J0.032
G3 X4.952 Y0.7225 I-0.4983 J0
G3 X4.9491 Y0.7516 I-0.4161 J-0.0268
G3 X4.944 Y0.7804 I-0.3801 J-0.0514
G3 X4.9373 Y0.8067 I-0.3232 J-0.0691
G3 X4.9284 Y0.8324 I-0.3076 J-0.0928
G3 X4.9181 Y0.8551 I-0.252 J-0.0999
G3 X4.9058 Y0.8767 I-0.2249 J-0.1141
G3 X4.8921 Y0.8959 I-0.1909 J-0.1218
G3 X4.8763 Y0.9135 I-0.1602 J-0.1276
G3 X4.8591 Y0.9287 I-0.1379 J-0.1385
G3 X4.8402 Y0.9418 I-0.1212 J-0.1544
G3 X4.8192 Y0.9531 I-0.1088 J-0.1784
G3 X4.7971 Y0.9618 I-0.085 J-0.1835
G3 X4.7732 Y0.9681 I-0.0682 J-0.2081
G3 X4.7487 Y0.9718 I-0.0472 J-0.2288
G3 X4.7219 Y0.9731 I-0.0269 J-0.2747
G3 X4.6944 Y0.9718 I0 J-0.2778
G3 X4.6698 Y0.968 I0.0226 J-0.2269
G3 X4.6458 Y0.9614 I0.0436 J-0.206
G3 X4.6239 Y0.9524 I0.0608 J-0.1793
G3 X4.6033 Y0.941 I0.0938 J-0.1933
G3 X4.5845 Y0.9276 I0.1085 J-0.1725
G3 X4.5674 Y0.9123 I0.1271 J-0.159
G3 X4.5517 Y0.8947 I0.1514 J-0.1507
G3 X4.538 Y0.8755 I0.1766 J-0.1407
G3 X4.5256 Y0.8538 I0.2121 J-0.1354
G3 X4.5154 Y0.8311 I0.2413 J-0.1223
G3 X4.5065 Y0.8055 I0.2984 J-0.1182
G3 X4.4997 Y0.7792 I0.3216 J-0.0968
G3 X4.4947 Y0.7507 I0.3729 J-0.0801
G3 X4.4918 Y0.7219 I0.4066 J-0.0555
G3 X4.4908 Y0.6905 I0.4804 J-0.0313
G0 Z0.125
G0 X5.1552 Y0.6905
G1 Z-0.01 F10
G2 X5.153 Y0.6348 I-0.7056 J0 F40
G2 X5.1469 Y0.5855 I-0.5592 J0.0443
G2 X5.1362 Y0.537 I-0.4973 J0.0842
G2 X5.1219 Y0.494 I-0.4061 J0.1107
G2 X5.1034 Y0.4526 I-0.4475 J0.1756
G2 X5.0825 Y0.4161 I-0.3674 J0.1859
G2 X5.058 Y0.3821 I-0.3264 J0.2094
G2 X5.0309 Y0.3521 I-0.2803 J0.2261
G2 X5.0006 Y0.3252 I-0.2579 J0.2609
G2 X4.9676 Y0.302 I-0.2269 J0.2867
G2 X4.9322 Y0.2824 I-0.1983 J0.3171
G2 X4.8933 Y0.266 I-0.1783 J0.3683
G2 X4.8529 Y0.2534 I-0.1576 J0.4351
G2 X4.8106 Y0.2443 I-0.1231 J0.4701
G2 X4.7676 Y0.239 I-0.0841 J0.4988
G2 X4.7219 Y0.2371 I-0.0457 J0.5609
G2 X4.6774 Y0.239 I0 J0.5346
G2 X4.6352 Y0.2443 I0.0407 J0.4884
G2 X4.5936 Y0.2534 I0.0806 J0.4691
G2 X4.5536 Y0.266 I0.1189 J0.4479
G2 X4.5149 Y0.2824 I0.1418 J0.3881
G2 X4.4795 Y0.302 I0.1683 J0.3468
G2 X4.4463 Y0.3252 I0.2011 J0.3229
G2 X4.4154 Y0.3521 I0.2387 J0.3054
G2 X4.3877 Y0.3821 I0.2524 J0.2608
G2 X4.3627 Y0.4161 I0.2987 J0.246
G2 X4.3414 Y0.4526 I0.3422 J0.2241
G2 X4.3225 Y0.494 I0.4215 J0.2176
G2 X4.3079 Y0.537 I0.3858 J0.1543
G2 X4.297 Y0.5855 I0.4777 J0.1328
G2 X4.2908 Y0.6348 I0.5427 J0.0937
G2 X4.2885 Y0.6905 I0.6897 J0.0557
G2 X4.2909 Y0.7462 I0.6678 J0
G2 X4.2973 Y0.7956 I0.5306 J-0.0444
G2 X4.3086 Y0.844 I0.473 J-0.0846
G2 X4.3237 Y0.8871 I0.3899 J-0.1124
G2 X4.3432 Y0.9285 I0.4519 J-0.1874
G2 X4.365 Y0.9652 I0.376 J-0.199
G2 X4.3904 Y0.9993 I0.3361 J-0.2236
G2 X4.4185 Y1.0297 I0.2923 J-0.2425
G2 X4.4497 Y1.0569 I0.2779 J-0.287
G2 X4.4829 Y1.0802 I0.2379 J-0.303
G2 X4.5184 Y1.1 I0.2055 J-0.3276
G2 X4.5567 Y1.1163 I0.1789 J-0.3656
G2 X4.5964 Y1.129 I0.1604 J-0.4356
G2 X4.6372 Y1.138 I0.1212 J-0.4502
G2 X4.6787 Y1.1434 I0.0819 J-0.4678
G2 X4.7219 Y1.1452 I0.0432 J-0.5057
G2 X4.7663 Y1.1434 I0 J-0.535
G2 X4.8085 Y1.138 I-0.0407 J-0.4886
G2 X4.8501 Y1.1289 I-0.0806 J-0.4692
G2 X4.8902 Y1.1163 I-0.1189 J-0.4478
G2 X4.9288 Y1.0999 I-0.1394 J-0.3816
G2 X4.9643 Y1.0802 I-0.1667 J-0.3421
G2 X4.9975 Y1.0568 I-0.2001 J-0.3191
G2 X5.0284 Y1.0297 I-0.2393 J-0.3033
G2 X5.0561 Y0.9993 I-0.2595 J-0.2651
G2 X5.0811 Y0.9652 I-0.3049 J-0.2492
G2 X5.1024 Y0.9285 I-0.3477 J-0.2267
G2 X5.1213 Y0.8871 I-0.4252 J-0.219
G2 X5.1358 Y0.844 I-0.3859 J-0.1543
G2 X5.1467 Y0.7956 I-0.4781 J-0.1328
G2 X5.1529 Y0.7462 I-0.5432 J-0.0937
G2 X5.1552 Y0.6905 I-0.6906 J-0.0557
G0 Z0.125
G0 X5.831 Y0.2547
G1 Z-0.01 F10
G3 X5.8176 Y0.2759 I-1.044 J-0.6457 F40
G3 X5.8023 Y0.2991 I-1.2661 J-0.8193
G3 X5.7865 Y0.3221 I-1.3802 J-0.9298
G3 X5.7688 Y0.347 I-1.648 J-1.1507
G3 X5.7507 Y0.3716 I-1.2024 J-0.8671
G3 X5.7315 Y0.3966 I-1.2587 J-0.9478
G3 X5.7118 Y0.4213 I-1.2783 J-1.0032
G3 X5.691 Y0.4462 I-1.3393 J-1.0938
G3 X5.6697 Y0.4708 I-1.3401 J-1.1372
G3 X5.6481 Y0.4949 I-1.3041 J-1.1488
G3 X5.6261 Y0.5186 I-1.2762 J-1.1671
G3 X5.6037 Y0.5417 I-1.2437 J-1.1807
G3 X5.5807 Y0.5643 I-0.7609 J-0.7501
G3 X5.5585 Y0.5849 I-0.6558 J-0.6866
G3 X5.5355 Y0.6048 I-0.5973 J-0.6668
G3 X5.5132 Y0.6227 I-0.5113 J-0.6113
G1 X5.5132 Y0.2547
G1 X5.3173 Y0.2547
G1 X5.3173 Y1.1251
G1 X5.5132 Y1.1251
G1 X5.5132 Y0.796
G3 X5.5514 Y0.8364 I-4.1871 J3.9914
G3 X5.59 Y0.8782 I-4.4359 J4.1481
G3 X5.6283 Y0.9203 I-4.5842 J4.207
G3 X5.6671 Y0.9637 I-4.8507 J4.3705
G2 X5.7058 Y1.0073 I26.9704 J-23.868
G2 X5.7417 Y1.0477 I23.1463 J-20.5506
G2 X5.7777 Y1.088 I21.3614 J-19.0327
G2 X5.8109 Y1.1251 I18.1034 J-16.1914
G1 X6.0433 Y1.1251
G2 X5.9984 Y1.0726 I-5.3969 J4.5615
G2 X5.9539 Y1.0215 I-5.1497 J4.4395
G2 X5.9089 Y0.9709 I-5.0078 J4.405
G2 X5.8643 Y0.9217 I-4.7755 J4.2874
G2 X5.8191 Y0.8729 I-4.3297 J3.9689
G2 X5.7721 Y0.8234 I-4.526 J4.244
G2 X5.7246 Y0.7743 I-4.6029 J4.4123
G2 X5.6753 Y0.7244 I-4.8095 J4.7102
G2 X5.7262 Y0.6798 I-0.8185 J-0.9847
G2 X5.7778 Y0.6296 I-0.9824 J-1.0622
G2 X5.8269 Y0.577 I-1.1027 J-1.0792
G2 X5.8769 Y0.5185 I-1.3152 J-1.1722
G2 X5.9244 Y0.458 I-1.6952 J-1.3829
G2 X5.9722 Y0.3929 I-1.9177 J-1.4551
G2 X6.0177 Y0.3262 I-2.064 J-1.4598
G2 X6.0634 Y0.2547 I-2.3302 J-1.5388
G1 X5.831 Y0.2547
G0 Z0.125
G0 X6.3404 Y0.6905
G1 Z-0.01 F10
G3 X6.3415 Y0.6586 I0.4971 J0 F40
G3 X6.3444 Y0.6296 I0.4109 J0.0265
G3 X6.3494 Y0.601 I0.3733 J0.0507
G3 X6.3561 Y0.575 I0.3139 J0.0676
G3 X6.365 Y0.5497 I0.3036 J0.0925
G3 X6.3753 Y0.5271 I0.2511 J0.1004
G3 X6.3876 Y0.5056 I0.2254 J0.1151
G3 X6.4013 Y0.4864 I0.1934 J0.124
G3 X6.417 Y0.4689 I0.1636 J0.1303
G3 X6.4342 Y0.4536 I0.1398 J0.1398
G3 X6.4529 Y0.4405 I0.1224 J0.1548
G3 X6.4736 Y0.4293 I0.109 J0.1765
G3 X6.4954 Y0.4206 I0.0819 J0.174
G3 X6.5194 Y0.4142 I0.0674 J0.205
G3 X6.5441 Y0.4105 I0.0471 J0.2296
G3 X6.5715 Y0.4092 I0.0275 J0.2849
G3 X6.5984 Y0.4105 I0 J0.2758
G3 X6.6229 Y0.4142 I-0.0227 J0.2323
G3 X6.6468 Y0.4206 I-0.0443 J0.2143
G3 X6.6689 Y0.4293 I-0.0629 J0.192
G3 X6.6898 Y0.4405 I-0.0881 J0.1899
G3 X6.7088 Y0.4536 I-0.1024 J0.1678
G3 X6.726 Y0.4689 I-0.1208 J0.154
G3 X6.7417 Y0.4864 I-0.1445 J0.1452
G3 X6.7555 Y0.5056 I-0.1798 J0.1433
G3 X6.7678 Y0.5271 I-0.2133 J0.1367
G3 X6.778 Y0.5497 I-0.2412 J0.1232
G3 X6.787 Y0.575 I-0.295 J0.1181
G3 X6.7937 Y0.601 I-0.3069 J0.0937
G3 X6.7987 Y0.6296 I-0.3679 J0.0794
G3 X6.8016 Y0.6586 I-0.4076 J0.0554
G3 X6.8027 Y0.6905 I-0.4955 J0.032
G3 X6.8016 Y0.7225 I-0.4983 J0
G3 X6.7987 Y0.7516 I-0.4161 J-0.0268
G3 X6.7937 Y0.7804 I-0.3801 J-0.0514
G3 X6.787 Y0.8067 I-0.3232 J-0.0691
G3 X6.778 Y0.8324 I-0.3076 J-0.0928
G3 X6.7678 Y0.8551 I-0.252 J-0.0999
G3 X6.7554 Y0.8767 I-0.2249 J-0.1141
G3 X6.7417 Y0.8959 I-0.1909 J-0.1218
G3 X6.726 Y0.9135 I-0.1602 J-0.1276
G3 X6.7088 Y0.9287 I-0.1379 J-0.1385
G3 X6.6898 Y0.9418 I-0.1212 J-0.1544
G3 X6.6689 Y0.9531 I-0.1088 J-0.1784
G3 X6.6468 Y0.9618 I-0.085 J-0.1835
G3 X6.6229 Y0.9681 I-0.0682 J-0.2081
G3 X6.5984 Y0.9718 I-0.0472 J-0.2288
G3 X6.5715 Y0.9731 I-0.0269 J-0.2747
G3 X6.5441 Y0.9718 I0 J-0.2778
G3 X6.5194 Y0.968 I0.0226 J-0.2269
G3 X6.4954 Y0.9614 I0.0436 J-0.206
G3 X6.4736 Y0.9524 I0.0608 J-0.1793
G3 X6.4529 Y0.941 I0.0938 J-0.1933
G3 X6.4342 Y0.9276 I0.1085 J-0.1725
G3 X6.417 Y0.9123 I0.1271 J-0.159
G3 X6.4013 Y0.8947 I0.1514 J-0.1507
G3 X6.3876 Y0.8755 I0.1766 J-0.1407
G3 X6.3753 Y0.8538 I0.2121 J-0.1354
G3 X6.3651 Y0.8311 I0.2413 J-0.1223
G3 X6.3561 Y0.8055 I0.2984 J-0.1182
G3 X6.3494 Y0.7792 I0.3216 J-0.0968
G3 X6.3444 Y0.7507 I0.3729 J-0.0801
G3 X6.3415 Y0.7219 I0.4066 J-0.0555
G3 X6.3404 Y0.6905 I0.4804 J-0.0313
G0 Z0.125
G0 X7.0049 Y0.6905
G1 Z-0.01 F10
G2 X7.0027 Y0.6348 I-0.7056 J0 F40
G2 X6.9965 Y0.5855 I-0.5592 J0.0443
G2 X6.9859 Y0.537 I-0.4973 J0.0842
G2 X6.9716 Y0.494 I-0.4061 J0.1107
G2 X6.953 Y0.4526 I-0.4475 J0.1756
G2 X6.9322 Y0.4161 I-0.3674 J0.1859
G2 X6.9077 Y0.3821 I-0.3264 J0.2094
G2 X6.8805 Y0.3521 I-0.2803 J0.2261
G2 X6.8503 Y0.3252 I-0.2579 J0.2609
G2 X6.8173 Y0.302 I-0.2269 J0.2867
G2 X6.7819 Y0.2824 I-0.1983 J0.3171
G2 X6.743 Y0.266 I-0.1783 J0.3683
G2 X6.7026 Y0.2534 I-0.1576 J0.4351
G2 X6.6602 Y0.2443 I-0.1231 J0.4701
G2 X6.6172 Y0.239 I-0.0841 J0.4988
G2 X6.5715 Y0.2371 I-0.0457 J0.5609
G2 X6.5271 Y0.239 I0 J0.5346
G2 X6.4849 Y0.2443 I0.0407 J0.4884
G2 X6.4433 Y0.2534 I0.0806 J0.4691
G2 X6.4032 Y0.266 I0.1189 J0.4479
G2 X6.3646 Y0.2824 I0.1418 J0.3881
G2 X6.3291 Y0.302 I0.1683 J0.3468
G2 X6.2959 Y0.3252 I0.2011 J0.3229
G2 X6.2651 Y0.3521 I0.2387 J0.3054
G2 X6.2374 Y0.3821 I0.2524 J0.2608
G2 X6.2123 Y0.4161 I0.2987 J0.246
G2 X6.191 Y0.4526 I0.3422 J0.2241
G2 X6.1721 Y0.494 I0.4215 J0.2176
G2 X6.1576 Y0.537 I0.3858 J0.1544
G2 X6.1467 Y0.5855 I0.4777 J0.1328
G2 X6.1405 Y0.6348 I0.5427 J0.0937
G2 X6.1382 Y0.6905 I0.6897 J0.0557
G2 X6.1405 Y0.7462 I0.6678 J0
G2 X6.147 Y0.7956 I0.5306 J-0.0444
G2 X6.1583 Y0.844 I0.473 J-0.0846
G2 X6.1734 Y0.8871 I0.3899 J-0.1124
G2 X6.1929 Y0.9285 I0.4519 J-0.1874
G2 X6.2147 Y0.9652 I0.376 J-0.199
G2 X6.2401 Y0.9993 I0.3361 J-0.2236
G2 X6.2682 Y1.0297 I0.2923 J-0.2425
G2 X6.2994 Y1.0569 I0.2779 J-0.287
G2 X6.3326 Y1.0802 I0.2379 J-0.303
G2 X6.3681 Y1.1 I0.2055 J-0.3276
G2 X6.4064 Y1.1163 I0.1789 J-0.3656
G2 X6.4461 Y1.129 I0.1604 J-0.4356
G2 X6.4869 Y1.138 I0.1212 J-0.4502
G2 X6.5284 Y1.1434 I0.0819 J-0.4678
G2 X6.5715 Y1.1452 I0.0432 J-0.5057
G2 X6.616 Y1.1434 I0 J-0.535
G2 X6.6582 Y1.138 I-0.0407 J-0.4886
G2 X6.6998 Y1.1289 I-0.0806 J-0.4692
G2 X6.7399 Y1.1163 I-0.1189 J-0.4478
G2 X6.7785 Y1.0999 I-0.1394 J-0.3816
G2 X6.814 Y1.0802 I-0.1667 J-0.3421
G2 X6.8471 Y1.0568 I-0.2001 J-0.3191
G2 X6.878 Y1.0297 I-0.2393 J-0.3033
G2 X6.9058 Y0.9993 I-0.2595 J-0.2651
G2 X6.9308 Y0.9652 I-0.3049 J-0.2492
G2 X6.9521 Y0.9285 I-0.3477 J-0.2267
G2 X6.971 Y0.8871 I-0.4252 J-0.219
G2 X6.9855 Y0.844 I-0.3859 J-0.1543
G2 X6.9964 Y0.7956 I-0.4781 J-0.1328
G2 X7.0026 Y0.7462 I-0.5432 J-0.0937
G2 X7.0049 Y0.6905 I-0.6906 J-0.0557
G0 Z0.125
G0 X7.9912 Y0.8965
G1 Z-0.01 F10
G2 X7.99 Y0.8728 I-0.237 J0 F40
G2 X7.9865 Y0.8497 I-0.2267 J0.0228
G2 X7.9807 Y0.8272 I-0.2234 J0.0459
G2 X7.9724 Y0.8048 I-0.2271 J0.0715
G2 X7.9623 Y0.7832 I-0.3646 J0.1563
G2 X7.9507 Y0.7617 I-0.3716 J0.1865
G2 X7.9379 Y0.7409 I-0.371 J0.2144
G2 X7.9234 Y0.7201 I-0.3849 J0.2528
G2 X7.9079 Y0.7 I-0.5278 J0.3898
G2 X7.8914 Y0.68 I-0.5353 J0.4282
G2 X7.8741 Y0.6607 I-0.5316 J0.4593
G2 X7.8556 Y0.6416 I-0.5427 J0.505
G1 X7.7815 Y0.57
G3 X7.7721 Y0.5611 I0.8861 J-0.9498
G3 X7.7618 Y0.5513 I1.0881 J-1.1433
G3 X7.7517 Y0.5413 I1.2053 J-1.2439
G3 X7.7406 Y0.5304 I1.4521 J-1.4741
G1 X7.6986 Y0.4858
G3 X7.6886 Y0.4744 I1.1214 J-0.996
G3 X7.6796 Y0.464 I0.9432 J-0.8208
G3 X7.6707 Y0.4534 I0.8658 J-0.7369
G3 X7.6628 Y0.4437 I0.7169 J-0.5953
G3 X7.6552 Y0.4338 I0.1702 J-0.1375
G3 X7.65 Y0.426 I0.0998 J-0.0716
G3 X7.6456 Y0.4178 I0.0757 J-0.046
G3 X7.6433 Y0.4117 I0.0391 J-0.0185
G1 X8.0176 Y0.4117
G1 X8.0176 Y0.2547
G1 X7.4373 Y0.2547
G2 X7.4363 Y0.2616 I0.1145 J0.0207
G2 X7.4354 Y0.2704 I0.1829 J0.0218
G2 X7.435 Y0.2792 I0.2268 J0.0161
G2 X7.4348 Y0.2899 I0.3344 J0.0107
G1 X7.4348 Y0.2998
G1 X7.4348 Y0.3081
G1 X7.4348 Y0.3148
G1 X7.4348 Y0.32
G2 X7.4361 Y0.3501 I0.3578 J0
G2 X7.4397 Y0.3778 I0.3087 J-0.026
G2 X7.4458 Y0.4051 I0.2878 J-0.0507
G2 X7.4543 Y0.4306 I0.2595 J-0.0719
G2 X7.4648 Y0.4553 I0.3938 J-0.1527
G2 X7.4767 Y0.4791 I0.3744 J-0.1733
G2 X7.4902 Y0.502 I0.3612 J-0.1964
G2 X7.5052 Y0.5241 I0.3512 J-0.2214
G2 X7.5213 Y0.5454 I0.4675 J-0.3386
G2 X7.5386 Y0.566 I0.457 J-0.3645
G2 X7.5568 Y0.5859 I0.4444 J-0.3892
G2 X7.5761 Y0.6051 I0.4388 J-0.4211
G1 X7.6546 Y0.6805
G3 X7.6697 Y0.6949 I-6.5538 J6.8409
G3 X7.6838 Y0.7086 I-5.8415 J6.0705
G3 X7.6979 Y0.7223 I-5.5113 J5.7006
G3 X7.7111 Y0.7351 I-4.8745 J5.0171
G3 X7.7242 Y0.7482 I-0.5266 J0.5392
G3 X7.7359 Y0.7606 I-0.4648 J0.4531
G3 X7.7474 Y0.7733 I-0.4416 J0.4084
G3 X7.7576 Y0.7854 I-0.388 J0.3389
G3 X7.7673 Y0.7979 I-0.2179 J0.1789
G3 X7.7755 Y0.8099 I-0.1921 J0.1404
G3 X7.7829 Y0.8223 I-0.1846 J0.1184
G3 X7.789 Y0.8343 I-0.1653 J0.0911
G3 X7.794 Y0.8468 I-0.1205 J0.0556
G3 X7.7975 Y0.859 I-0.1118 J0.0384
G3 X7.7996 Y0.8715 I-0.111 J0.0253
G3 X7.8003 Y0.884 I-0.1104 J0.0125
G3 X7.798 Y0.9112 I-0.1655 J0
G3 X7.7924 Y0.9311 I-0.0937 J-0.0156
G3 X7.7824 Y0.9488 I-0.0702 J-0.0283
G3 X7.7689 Y0.9618 I-0.0509 J-0.0389
G3 X7.7525 Y0.9716 I-0.064 J-0.0889
G3 X7.7337 Y0.9788 I-0.0523 J-0.1085
G3 X7.714 Y0.9829 I-0.0372 J-0.1282
G3 X7.691 Y0.9844 I-0.023 J-0.1742
G3 X7.6741 Y0.9838 I0 J-0.2082
G3 X7.6582 Y0.9818 I0.0152 J-0.1867
G3 X7.6426 Y0.9784 I0.0299 J-0.1776
G3 X7.6276 Y0.9738 I0.0434 J-0.166
G3 X7.613 Y0.9681 I0.124 J-0.3427
G3 X7.5994 Y0.9621 I0.1248 J-0.3035
G3 X7.586 Y0.9556 I0.1317 J-0.2831
G3 X7.5736 Y0.9486 I0.1322 J-0.2521
G3 X7.5615 Y0.9412 I0.2233 J-0.3784
G3 X7.5508 Y0.9342 I0.1896 J-0.2988
G3 X7.5405 Y0.9268 I0.179 J-0.2609
G3 X7.5315 Y0.9198 I0.1505 J-0.2014
G3 X7.5228 Y0.9125 I0.4664 J-0.5685
G3 X7.5161 Y0.9067 I0.2834 J-0.3348
G3 X7.5096 Y0.9008 I0.2157 J-0.2447
G3 X7.5052 Y0.8965 I0.1113 J-0.1196
G1 X7.4122 Y1.0271
G2 X7.4408 Y1.0516 I0.3033 J-0.3254
G2 X7.472 Y1.0741 I0.2859 J-0.3642
G2 X7.505 Y1.0939 I0.2634 J-0.4
G2 X7.541 Y1.1119 I0.2525 J-0.4598
G2 X7.5784 Y1.1265 I0.1528 J-0.3372
G2 X7.6171 Y1.1369 I0.115 J-0.3507
G2 X7.6567 Y1.1431 I0.078 J-0.3692
G2 X7.6986 Y1.1452 I0.0419 J-0.4097
G2 X7.7368 Y1.1441 I0 J-0.6209
G2 X7.7698 Y1.1408 I-0.0288 J-0.4669
G2 X7.8025 Y1.1351 I-0.0537 J-0.4022
G2 X7.8304 Y1.1276 I-0.0656 J-0.3011
G2 X7.8576 Y1.1176 I-0.0975 J-0.3061
G2 X7.8808 Y1.1064 I-0.0996 J-0.2366
G2 X7.9028 Y1.0929 I-0.1113 J-0.2042
G2 X7.9215 Y1.078 I-0.1143 J-0.1635
G2 X7.9383 Y1.0611 I-0.1312 J-0.1467
G2 X7.9526 Y1.0425 I-0.1419 J-0.1243
G2 X7.9645 Y1.0224 I-0.1576 J-0.1068
G2 X7.9743 Y1.0002 I-0.1832 J-0.0937
G2 X7.9816 Y0.9769 I-0.2296 J-0.085
G2 X7.987 Y0.9513 I-0.2735 J-0.0712
G2 X7.9901 Y0.9253 I-0.3042 J-0.0498
G2 X7.9912 Y0.8965 I-0.3724 J-0.0288
G0 Z0.125
(remove M5 and M30)

File diff suppressed because it is too large Load Diff

View File

@ -1,437 +0,0 @@
% ----------------------------------------------------------------------------------------
% The MIT License (MIT)
%
% Copyright (c) 2014 Sungeun K. Jeon
%
% Permission is hereby granted, free of charge, to any person obtaining a copy
% of this software and associated documentation files (the "Software"), to deal
% in the Software without restriction, including without limitation the rights
% to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
% copies of the Software, and to permit persons to whom the Software is
% furnished to do so, subject to the following conditions:
%
% The above copyright notice and this permission notice shall be included in
% all copies or substantial portions of the Software.
%
% THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
% IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
% FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
% AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
% LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
% OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
% THE SOFTWARE.
% ----------------------------------------------------------------------------------------
% This MATLAB script was written for the purpose of being a GRBL planner simulator. This
% simulator is a rough representation of the actual workings of Grbl on the Arduino, but
% was used to hone and proof the actual planner by providing quick visual feedback on its
% functionality when experimented on. This script should be considered for educational
% purposes only. This script requires and executes a pre-parsed g-code file from the
% matlab_convert.py script that is in a specific non-g-code format.
% There will be two figures plotted. The first is the line motion paths of the complete
% g-code program. The second is a representation of Grbl's planner buffer as new line
% motions are fed to it, plotting the velocity profiles the stepper motors will execute.
% Every time the user inputs an <Enter>, this feeds the simulator planner one line motion
% block. The left side is the first block in the buffer and the one that will be executed
% by the stepper module first. The right side is the end of the planner buffer, where the
% most recent streamed block is appended onto the planner buffer. Grbl's planner
% optimizes the velocity profiles between the beginning and end of the buffer based on
% the acceleration limits, intended velocity/feedrate, and line motion junction angles
% with their corresponding velocity limits (i.e. junctions with acute angles needs to come
% to a complete stop vs straight junctions can continue through at full speed.)
% ----------------------------------------------------------------------------------------
% Main function
% NOTE: This is just a way to keep all functions in one place, but all non-global variables
% are cleared as soon as this script completes.
function main()
% Load pre-parsed gcode moves.
close all;
warning off;
clearvars -global
fid = fopen('matlab.gcode','r');
gcode = textscan(fid,'%d8%f32%f32%f32%f32');
nblock = length(gcode{1});
% Plot all g-code moves.
figure
line(gcode{3},gcode{4},gcode{5});
axis equal;
% axis([min(gcode{3}) max(gcode{3}) min(gcode{4}) max(gcode{4}) min(gcode{5}) max(gcode{5})]);
title('G-code programming line motions');
view(3);
% Set up figure for planner queue
figure
% Print help.
disp('<NOTE: Press Enter to Advance One G-Code Line Motion>');
disp(' BLUE line indicates completed planner blocks that require no recalculation.');
disp(' RED line indicates planner blocks that have been recalculated.');
disp(' GREEN line indicates the location of the BPLANNED pointer. Always a recalculated block.');
disp(' BLACK dotted-line and ''x'' indicates block nominal speed and max junction velocity, respectively.');
disp(' CYAN ''.'' indicates block initial entry speed.');
% Define Grbl settings.
BUFFER_SIZE = 18; % Number of planner blocks in its ring buffer.
steps_per_mm = 200;
seekrate = 2500; % mm/min
acceleration = [100 100 100]; % mm/sec^2 [ X Y Z ] axes
junction_deviation = 0.1; % mm. See Grbl documentation on this parameter.
inch_2_mm = 25.4;
ACCELERATION_TICKS_PER_SECOND = 100;
gcode{2} = gcode{2};
gcode{2} = inch_2_mm*gcode{2};
gcode{3} = inch_2_mm*gcode{3};
gcode{4} = inch_2_mm*gcode{4};
gcode{5} = inch_2_mm*gcode{5};
% Initialize blocks
block.steps = [];
block.step_event_count = [];
block.delta_mm = [];
block.millimeters = [];
block.acceleration = [];
block.speed = [];
block.nominal_speed = [];
block.max_entry_speed = [];
block.entry_speed = [];
block.recalculate_flag = false;
for i = 2:BUFFER_SIZE
block(i) = block(1);
end
% Initialize planner
position = [0 0 0];
prev_unit_vec = [0 0 0];
previous_nominal_speed = 0;
pos = 0;
% BHEAD and BTAIL act as pointers to the block head and tail.
% BPLANNED acts as a pointer of the location of the end of a completed/optimized plan.
bhead = 1;
btail = 1;
bplanned = 1;
global block bhead btail bplanned nind acceleration BUFFER_SIZE pos ACCELERATION_TICKS_PER_SECOND
% Main loop. Simulates plan_buffer_line(). All of the precalculations for the newest incoming
% block occurs here. Anything independent of the planner changes.
for i = 1:nblock
target = round([gcode{3}(i) gcode{4}(i) gcode{5}(i)].*steps_per_mm);
if gcode{1}(i) == 1
feedrate = gcode{2}(i);
else
feedrate = seekrate;
end
nind = next_block_index(bhead);
if nind == btail
% Simulate a constantly full buffer. Move buffer tail.
bind = next_block_index(btail);
% Push planned pointer if encountered. Prevents it from looping back around the ring buffer.
if btail == bplanned; bplanned = bind; end
btail = bind;
end
block(bhead).steps = abs(target-position);
block(bhead).step_event_count = max(block(bhead).steps);
% Bail if this is a zero-length block
if block(bhead).step_event_count == 0
disp(['Zero-length block in line ',int2str(i)]);
else
% Compute path vector in terms of absolute step target and current positions
delta_mm = single((target-position)./steps_per_mm);
block(bhead).millimeters = single(norm(delta_mm));
inverse_millimeters = single(1/block(bhead).millimeters);
% Compute path unit vector
unit_vec = delta_mm/block(bhead).millimeters;
% Calculate speed in mm/minute for each axis
inverse_minute = single(feedrate * inverse_millimeters);
block(bhead).speed = delta_mm*inverse_minute;
block(bhead).nominal_speed = block(bhead).millimeters*inverse_minute;
% Calculate block acceleration. Operates on absolute value of unit vector.
[max_acc,ind] = max(abs(unit_vec)./acceleration); % Determine limiting acceleration
block(bhead).acceleration = acceleration(ind)/abs(unit_vec(ind));
% Compute maximum junction speed
block(bhead).max_entry_speed = 0.0;
if previous_nominal_speed > 0.0
cos_theta = dot(-previous_unit_vec,unit_vec);
if (cos_theta < 0.95)
block(bhead).max_entry_speed = min([block(bhead).nominal_speed,previous_nominal_speed]);
if (cos_theta > -0.95)
sin_theta_d2 = sqrt(0.5*(1.0-cos_theta));
block(bhead).max_entry_speed = min([block(bhead).max_entry_speed,sqrt(block(bhead).acceleration*3600*junction_deviation*sin_theta_d2/(1.0-sin_theta_d2))]);
end
end
end
block(bhead).entry_speed = 0; % Just initialize. Set accurately in the replanning function.
block(bhead).recalculate_flag = true; % Plotting flag to indicate this block has been updated.
previous_unit_vec = unit_vec;
previous_nominal_speed = block(bhead).nominal_speed;
position = target;
bhead = nind; % Block complete. Push buffer pointer.
planner_recalculate();
plot_buffer_velocities();
end
end
return
% Computes the next block index in the planner ring buffer
function block_index = next_block_index(block_index)
global BUFFER_SIZE
block_index = block_index + 1;
if block_index > BUFFER_SIZE
block_index = 1;
end
return
% Computes the previous block index in the planner ring buffer
function block_index = prev_block_index(block_index)
global BUFFER_SIZE
block_index = block_index-1;
if block_index < 1
block_index = BUFFER_SIZE;
end
return
% Planner recalculate function. The magic happens here.
function planner_recalculate(block)
global block bhead btail bplanned acceleration
bind = prev_block_index(bhead);
if bind == bplanned; return; end % Bail, if only one block in buffer. Can't be operated on.
% Reverse Pass: Coarsely maximize all possible deceleration curves back-planning from the last
% block in buffer. Cease planning when the last optimal planned or tail pointer is reached.
% NOTE: Forward pass will later refine and correct the reverse pass to create an optimal plan.
next = [];
curr = bind; % Last block in buffer.
% Calculate maximum entry speed for last block in buffer, where the exit speed is always zero.
block(curr).entry_speed = min([block(curr).max_entry_speed,sqrt(2*block(curr).acceleration*60*60*block(curr).millimeters)]);
bind = prev_block_index(bind); % Btail or second to last block
if (bind == bplanned)
% Only two plannable blocks in buffer. Reverse pass complete.
% Check if the first block is the tail. If so, notify stepper module to update its current parameters.
% if bind == btail; update_tail_block; end
else
% Three or more plannable blocks in buffer. Loop it.
while bind ~= bplanned % Loop until bplanned point hits. Replans to last plan point.
next = curr;
curr = bind;
bind = prev_block_index( bind ); % Previous block pointer.
% Check if the first block is the tail. If so, notify stepper module to update its current parameters.
% if bind == btail; update_tail_block; end
% Compute maximum entry speed decelerating over the current block from its exit speed.
if block(curr).entry_speed ~= block(curr).max_entry_speed
block(curr).recalculate_flag = true; % Plotting flag to indicate this block has been updated.
block(curr).entry_speed = min([ block(curr).max_entry_speed,...
sqrt(block(next).entry_speed^2 + 2*block(curr).acceleration*60*60*block(curr).millimeters)]);
end
end
end
% For two blocks, reverse pass is skipped, but forward pass plans second block entry speed
% onward. This prevents the first, or the potentially executing block, from being over-written.
% NOTE: Can never be bhead, since bsafe is always in active buffer.
next = bplanned;
bind = next_block_index(bplanned); % Start at bplanned
while bind ~= bhead
curr = next;
next = bind;
% An acceleration block is always an optimally planned block since it starts from the first
% block's current speed or a maximum junction speed. Compute accelerations from this block
% and update the next block's entry speed.
if (block(curr).entry_speed < block(next).entry_speed)
% Once speed is set by forward planner, the plan for this block is finished and optimal.
% Increment the planner pointer forward one block.
entry_speed = sqrt(block(curr).entry_speed^2 + 2*block(curr).acceleration*60*60*block(curr).millimeters);
if (block(next).entry_speed > entry_speed)
block(next).entry_speed = entry_speed;
bplanned = bind;
end
end
% Check if the next block entry speed is at max_entry_speed. If so, move the planned pointer, since
% this entry speed cannot be improved anymore and all prior blocks have been completed and optimally planned.
if block(next).entry_speed == block(next).max_entry_speed
bplanned = bind;
end
% Recalculate trapezoid can be installed here, since it scans through all of the plannable blocks.
% NOTE: Eventually this will only be computed when being executed.
bind = next_block_index( bind );
end
return
% ----------------------------------------------------------------------------------------
% PLOTTING FUNCTIONS
% Plots the entire buffer plan into a MATLAB figure to visual the plan.
% BLUE line indicates completed planner blocks that require no recalculation.
% RED line indicates planner blocks that have been recalculated.
% GREEN line indicates the location of the BPLANNED pointer. Always a recalculated block.
% BLACK dotted-line and 'x' indicates block nominal speed and max junction velocity, respectively.
% CYAN '.' indicates block initial entry speed.
function plot_buffer_velocities()
global block bhead btail bplanned acceleration pos ACCELERATION_TICKS_PER_SECOND
bind = btail;
curr = [];
next = [];
pos_initial = 0;
pos = 0;
while bind ~= bhead
curr = next;
next = bind;
hold on;
if ~isempty(curr)
accel_d = estimate_acceleration_distance(block(curr).entry_speed, block(curr).nominal_speed, block(curr).acceleration*60*60);
decel_d = estimate_acceleration_distance(block(curr).nominal_speed, block(next).entry_speed,-block(curr).acceleration*60*60);
plateau_d = block(curr).millimeters-accel_d-decel_d;
if plateau_d < 0
accel_d = intersection_distance(block(curr).entry_speed, block(next).entry_speed, block(curr).acceleration*60*60, block(curr).millimeters);
if accel_d < 0
accel_d = 0;
elseif accel_d > block(curr).millimeters
accel_d = block(curr).millimeters;
end
plateau_d = 0;
end
color = 'b';
if (block(curr).recalculate_flag || block(next).recalculate_flag)
block(curr).recalculate_flag = false;
color = 'r';
end
if bplanned == curr
color = 'g';
end
plot_trap(pos,block(curr).entry_speed,block(next).entry_speed,block(curr).nominal_speed,block(curr).acceleration,accel_d,plateau_d,block(curr).millimeters,color)
plot([pos pos+block(curr).millimeters],block(curr).nominal_speed*[1 1],'k:') % BLACK dotted indicates
plot(pos,block(curr).max_entry_speed,'kx')
pos = pos + block(curr).millimeters;
plot(pos,block(next).entry_speed,'c.');
end
bind = next_block_index( bind );
end
accel_d = estimate_acceleration_distance(block(next).entry_speed, block(next).nominal_speed, block(next).acceleration*60*60);
decel_d = estimate_acceleration_distance(block(next).nominal_speed, 0, -block(next).acceleration*60*60);
plateau_d = block(next).millimeters-accel_d-decel_d;
if plateau_d < 0
accel_d = intersection_distance(block(next).entry_speed, 0, block(next).acceleration*60*60, block(next).millimeters);
if accel_d < 0
accel_d = 0;
elseif accel_d > block(next).millimeters
accel_d = block(next).millimeters;
end
plateau_d = 0;
end
block(next).recalculate_flag = false;
color = 'r';
if bplanned == next
color= 'g';
end
plot_trap(pos,block(next).entry_speed,0,block(next).nominal_speed,block(next).acceleration,accel_d,plateau_d,block(next).millimeters,color)
plot([pos pos+block(next).millimeters],block(next).nominal_speed*[1 1],'k:')
plot(pos,block(next).max_entry_speed,'kx')
plot(pos,block(next).entry_speed,'.');
pos = pos + block(next).millimeters;
plot(pos,0,'rx');
xlabel('mm');
ylabel('mm/sec');
xlim([pos_initial pos])
title('Planner buffer optimized velocity profile');
pause();
hold off;
plot(pos,0)
return
function d_a = estimate_acceleration_distance(initial_rate, target_rate, acceleration,rate_delta)
d_a = (target_rate*target_rate-initial_rate*initial_rate)/(2*acceleration);
return
function d_i = intersection_distance(initial_rate, final_rate, acceleration, distance, rate_delta)
d_i = (2*acceleration*distance-initial_rate*initial_rate+final_rate*final_rate)/(4*acceleration);
return
% Simply plots the ac/de-celeration curves and plateaus of a trapezoid.
function plot_trap(pos,initial_rate,final_rate,rate,accel,accel_d,plateau_d,millimeters,color)
dx = 1.0; % Line segment length
linex = [pos]; liney = [initial_rate];
% Acceleration
np = floor(accel_d/dx);
if np
v = initial_rate;
for i = 1:np
v = sqrt(v^2+2*accel*60*60*dx);
linex = [linex pos+i*dx];
liney = [liney v];
end
end
% Plateau
v = sqrt(initial_rate^2 + 2*accel*60*60*accel_d);
if v < rate
rate = v;
end
linex = [linex pos+[accel_d accel_d+plateau_d]];
liney = [liney [rate rate]];
% Deceleration
np = floor((millimeters-accel_d-plateau_d)/dx);
if np
v = rate;
for i = 1:np
v = sqrt(v^2-2*accel*60*60*dx);
linex = [linex pos+i*dx+accel_d+plateau_d];
liney = [liney v];
end
end
linex = [linex pos+millimeters];
liney = [ liney final_rate];
plot(linex,liney,color);
return

File diff suppressed because it is too large Load Diff

View File

@ -1,270 +0,0 @@
#!/usr/bin/env python
"""\
The MIT License (MIT)
Copyright (c) 2014 Sungeun K. Jeon
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.
----------------------------------------------------------------------------------------
"""
"""\
G-code preprocessor for the grbl_sim.m MATLAB script. Parses the g-code program to a
specific file format for the MATLAB script to use. Based on PreGrbl by @chamnit.
How to use: When running this python script, it will process the g-code program under
the filename "test.gcode" (may be changed below) and produces a file called "matlab.gcode"
that the grbl_sim.m MATLAB script will search for and execute.
"""
import re
from math import *
from copy import *
# -= SETTINGS =-
filein = 'test.gcode' # Input file name
fileout = 'matlab.gcode' # Output file name
ndigits_in = 4 # inch significant digits after '.'
ndigits_mm = 2 # mm significant digits after '.'
# mm_per_arc_segment = 0.38 # mm per arc segment
arc_tolerance = 0.00005*25.4
n_arc_correction = 20
inch2mm = 25.4 # inch to mm conversion scalar
verbose = False # Verbose flag to show all progress
remove_unsupported = True # Removal flag for all unsupported statements
# Initialize parser state
gc = { 'current_xyz' : [0,0,0],
'feed_rate' : 0, # F0
'motion_mode' : 'SEEK', # G00
'plane_axis' : [0,1,2], # G17
'inches_mode' : False, # G21
'inverse_feedrate_mode' : False, # G94
'absolute_mode' : True} # G90
def unit_conv(val) : # Converts value to mm
if gc['inches_mode'] : val *= inch2mm
return(val)
def fout_conv(val) : # Returns converted value as rounded string for output file.
if gc['inches_mode'] : return( str(round(val/inch2mm,ndigits_in)) )
else : return( str(round(val,ndigits_mm)) )
# Open g-code file
fin = open(filein,'r');
fout = open(fileout,'w');
# Iterate through g-code file
l_count = 0
for line in fin:
l_count += 1 # Iterate line counter
# Strip comments/spaces/tabs/new line and capitalize. Comment MSG not supported.
block = re.sub('\s|\(.*?\)','',line).upper()
block = re.sub('\\\\','',block) # Strip \ block delete character
block = re.sub('%','',block) # Strip % program start/stop character
if len(block) == 0 : # Ignore empty blocks
print "Skipping: " + line.strip()
else : # Process valid g-code clean block. Assumes no block delete characters or comments
g_cmd = re.findall(r'[^0-9\.\-]+',block) # Extract block command characters
g_num = re.findall(r'[0-9\.\-]+',block) # Extract block numbers
# G-code block error checks
# if len(g_cmd) != len(g_num) : print block; raise Exception('Invalid block. Unbalanced word and values.')
if 'N' in g_cmd :
if g_cmd[0]!='N': raise Exception('Line number must be first command in line.')
if g_cmd.count('N') > 1: raise Exception('More than one line number in block.')
g_cmd = g_cmd[1:] # Remove line number word
g_num = g_num[1:]
# Block item repeat checks? (0<=n'M'<5, G/M modal groups)
# Initialize block state
blk = { 'next_action' : 'DEFAULT',
'absolute_override' : False,
'target_xyz' : deepcopy(gc['current_xyz']),
'offset_ijk' : [0,0,0],
'radius_mode' : False,
'unsupported': [] }
# Pass 1
for cmd,num in zip(g_cmd,g_num) :
fnum = float(num)
inum = int(fnum)
if cmd is 'G' :
if inum is 0 : gc['motion_mode'] = 'SEEK'
elif inum is 1 : gc['motion_mode'] = 'LINEAR'
elif inum is 2 : gc['motion_mode'] = 'CW_ARC'
elif inum is 3 : gc['motion_mode'] = 'CCW_ARC'
elif inum is 4 : blk['next_action'] = 'DWELL'
elif inum is 17 : gc['plane_axis'] = [0,1,2] # Select XY Plane
elif inum is 18 : gc['plane_axis'] = [0,2,1] # Select XZ Plane
elif inum is 19 : gc['plane_axis'] = [1,2,0] # Select YZ Plane
elif inum is 20 : gc['inches_mode'] = True
elif inum is 21 : gc['inches_mode'] = False
elif inum in [28,30] : blk['next_action'] = 'GO_HOME'
elif inum is 53 : blk['absolute_override'] = True
elif inum is 54 : pass
elif inum is 80 : gc['motion_mode'] = 'MOTION_CANCEL'
elif inum is 90 : gc['absolute_mode'] = True
elif inum is 91 : gc['absolute_mode'] = False
elif inum is 92 : blk['next_action'] = 'SET_OFFSET'
elif inum is 93 : gc['inverse_feedrate_mode'] = True
elif inum is 94 : gc['inverse_feedrate_mode'] = False
else :
print 'Unsupported command ' + cmd + num + ' on line ' + str(l_count)
if remove_unsupported : blk['unsupported'].append(zip(g_cmd,g_num).index((cmd,num)))
elif cmd is 'M' :
if inum in [0,1] : pass # Program Pause
elif inum in [2,30,60] : pass # Program Completed
elif inum is 3 : pass # Spindle Direction 1
elif inum is 4 : pass # Spindle Direction -1
elif inum is 5 : pass # Spindle Direction 0
else :
print 'Unsupported command ' + cmd + num + ' on line ' + str(l_count)
if remove_unsupported : blk['unsupported'].append(zip(g_cmd,g_num).index((cmd,num)))
elif cmd is 'T' : pass # Tool Number
# Pass 2
for cmd,num in zip(g_cmd,g_num) :
fnum = float(num)
if cmd is 'F' : gc['feed_rate'] = unit_conv(fnum) # Feed Rate
elif cmd in ['I','J','K'] : blk['offset_ijk'][ord(cmd)-ord('I')] = unit_conv(fnum) # Arc Center Offset
elif cmd is 'N' : pass
elif cmd is 'P' : p = fnum # Misc value parameter
elif cmd is 'R' : r = unit_conv(fnum); blk['radius_mode'] = True # Arc Radius Mode
elif cmd is 'S' : pass # Spindle Speed
elif cmd in ['X','Y','Z'] : # Target Coordinates
if (gc['absolute_mode'] | blk['absolute_override']) :
blk['target_xyz'][ord(cmd)-ord('X')] = unit_conv(fnum)
else :
blk['target_xyz'][ord(cmd)-ord('X')] += unit_conv(fnum)
# Execute actions
if blk['next_action'] is 'GO_HOME' :
gc['current_xyz'] = deepcopy(blk['target_xyz']) # Update position
elif blk['next_action'] is 'SET_OFFSET' :
pass
elif blk['next_action'] is 'DWELL' :
if p < 0 : raise Exception('Dwell time negative.')
else : # 'DEFAULT'
if gc['motion_mode'] is 'SEEK' :
fout.write('0 '+fout_conv(gc['feed_rate']))
fout.write(' '+fout_conv(blk['target_xyz'][0]))
fout.write(' '+fout_conv(blk['target_xyz'][1]))
fout.write(' '+fout_conv(blk['target_xyz'][2]))
fout.write('\n')
gc['current_xyz'] = deepcopy(blk['target_xyz']) # Update position
elif gc['motion_mode'] is 'LINEAR' :
fout.write('1 '+fout_conv(gc['feed_rate']))
fout.write(' '+fout_conv(blk['target_xyz'][0]))
fout.write(' '+fout_conv(blk['target_xyz'][1]))
fout.write(' '+fout_conv(blk['target_xyz'][2]))
fout.write('\n')
gc['current_xyz'] = deepcopy(blk['target_xyz']) # Update position
elif gc['motion_mode'] in ['CW_ARC','CCW_ARC'] :
axis = gc['plane_axis']
# Convert radius mode to ijk mode
if blk['radius_mode'] :
x = blk['target_xyz'][axis[0]]-gc['current_xyz'][axis[0]]
y = blk['target_xyz'][axis[1]]-gc['current_xyz'][axis[1]]
if not (x==0 and y==0) : raise Exception('Same target and current XYZ not allowed in arc radius mode.')
h_x2_div_d = -sqrt(4 * r*r - x*x - y*y)/hypot(x,y)
if isnan(h_x2_div_d) : raise Exception('Floating point error in arc conversion')
if gc['motion_mode'] is 'CCW_ARC' : h_x2_div_d = -h_x2_div_d
if r < 0 : h_x2_div_d = -h_x2_div_d
blk['offset_ijk'][axis[0]] = (x-(y*h_x2_div_d))/2;
blk['offset_ijk'][axis[1]] = (y+(x*h_x2_div_d))/2;
else :
radius = sqrt(blk['offset_ijk'][axis[0]]**2+blk['offset_ijk'][axis[1]]**2)
center_axis0 = gc['current_xyz'][axis[0]]+blk['offset_ijk'][axis[0]]
center_axis1 = gc['current_xyz'][axis[1]]+blk['offset_ijk'][axis[1]]
linear_travel = blk['target_xyz'][axis[2]]-gc['current_xyz'][axis[2]]
r_axis0 = -blk['offset_ijk'][axis[0]]
r_axis1 = -blk['offset_ijk'][axis[1]]
rt_axis0 = blk['target_xyz'][axis[0]] - center_axis0;
rt_axis1 = blk['target_xyz'][axis[1]] - center_axis1;
clockwise_sign = 1
if gc['motion_mode'] is 'CW_ARC' : clockwise_sign = -1
angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1)
if gc['motion_mode'] is 'CW_ARC' :
if angular_travel >= 0 :
angular_travel -= 2*pi
else :
if angular_travel <= 0 :
angular_travel += 2*pi
millimeters_of_travel = sqrt((angular_travel*radius)**2 + abs(linear_travel)**2)
mm_per_arc_segment = sqrt(4*(2*radius*arc_tolerance-arc_tolerance**2))
segments = int(millimeters_of_travel/mm_per_arc_segment)
print segments
print l_count
theta_per_segment = angular_travel/segments
linear_per_segment = linear_travel/segments
cos_T = 1-0.5*theta_per_segment*theta_per_segment
sin_T = theta_per_segment-theta_per_segment**3/6
print(fout_conv(mm_per_arc_segment))
print theta_per_segment*180/pi
arc_target = [0,0,0]
arc_target[axis[2]] = gc['current_xyz'][axis[2]]
count = 0
for i in range(1,segments+1) :
if i < segments :
if count < n_arc_correction :
r_axisi = r_axis0*sin_T + r_axis1*cos_T
r_axis0 = r_axis0*cos_T - r_axis1*sin_T
r_axis1 = deepcopy(r_axisi)
count += 1
else :
cos_Ti = cos((i-1)*theta_per_segment)
sin_Ti = sin((i-1)*theta_per_segment)
print n_arc_correction*(r_axis0 -( -blk['offset_ijk'][axis[0]]*cos_Ti + blk['offset_ijk'][axis[1]]*sin_Ti))
print n_arc_correction*(r_axis1 -( -blk['offset_ijk'][axis[0]]*sin_Ti - blk['offset_ijk'][axis[1]]*cos_Ti))
cos_Ti = cos(i*theta_per_segment)
sin_Ti = sin(i*theta_per_segment)
r_axis0 = -blk['offset_ijk'][axis[0]]*cos_Ti + blk['offset_ijk'][axis[1]]*sin_Ti
r_axis1 = -blk['offset_ijk'][axis[0]]*sin_Ti - blk['offset_ijk'][axis[1]]*cos_Ti
count = 0
arc_target[axis[0]] = center_axis0 + r_axis0
arc_target[axis[1]] = center_axis1 + r_axis1
arc_target[axis[2]] += linear_per_segment
else :
arc_target = deepcopy(blk['target_xyz']) # Last segment at target_xyz
# Write only changed variables.
fout.write('1 '+fout_conv(gc['feed_rate']))
fout.write(' '+fout_conv(arc_target[0]))
fout.write(' '+fout_conv(arc_target[1]))
fout.write(' '+fout_conv(arc_target[2]))
fout.write('\n')
gc['current_xyz'] = deepcopy(arc_target) # Update position
print 'Done!'
# Close files
fin.close()
fout.close()

File diff suppressed because it is too large Load Diff

View File

@ -1,31 +0,0 @@
(Machine settings provided by @kikigey89)
$0=87.489 (x, step/mm)
$1=87.489 (y, step/mm)
$2=1280.000 (z, step/mm)
$3=1000.000 (x max rate, mm/min)
$4=1000.000 (y max rate, mm/min)
$5=500.000 (z max rate, mm/min)
$6=10.000 (x accel, mm/sec^2)
$7=10.000 (y accel, mm/sec^2)
$8=10.000 (z accel, mm/sec^2)
$9=211.000 (x max travel, mm)
$10=335.000 (y max travel, mm)
$11=70.000 (z max travel, mm)
$12=20 (step pulse, usec)
$13=160 (step port invert mask:10100000)
$14=160 (dir port invert mask:10100000)
$15=50 (step idle delay, msec)
$16=0.010 (junction deviation, mm)
$17=0.002 (arc tolerance, mm)
$19=0 (report inches, bool)
$20=1 (auto start, bool)
$21=0 (invert step enable, bool)
$22=0 (invert limit pins, bool)
$23=0 (soft limits, bool)
$24=0 (hard limits, bool)
$25=0 (homing cycle, bool)
$26=0 (homing dir invert mask:00000000)
$27=50.000 (homing feed, mm/min)
$28=500.000 (homing seek, mm/min)
$29=10 (homing debounce, msec)
$30=3.000 (homing pull-off, mm)

View File

@ -1,25 +0,0 @@
import random
import serial
import time
ser = serial.Serial('/dev/tty.usbmodem24111', 115200, timeout=0.001)
time.sleep(1)
outstanding = 0
data = ''
while True:
time.sleep(0.1)
data += ser.read()
pos = data.find('\n')
if pos == -1:
line = ''
else:
line = data[0:pos + 1]
data = data[pos + 1:]
if line == '' and outstanding < 3:
while outstanding < 3:
ser.write("G0 Z%0.3f\n" % (0.01 * (random.random() - 0.5)))
#ser.write("M3\n")
outstanding += 1
continue
if line == 'ok\r\n':
outstanding -= 1
print outstanding, repr(line.rstrip())