├── .gitignore ├── COPYING ├── Makefile ├── README.md ├── build └── .gitignore ├── doc ├── csv │ ├── alarm_codes_en_US.csv │ ├── build_option_codes_en_US.csv │ ├── error_codes_en_US.csv │ └── setting_codes_en_US.csv ├── log │ ├── commit_log_v0.7.txt │ ├── commit_log_v0.8c.txt │ ├── commit_log_v0.9g.txt │ ├── commit_log_v0.9i.txt │ ├── commit_log_v0.9j.txt │ ├── commit_log_v1.0b.txt │ ├── commit_log_v1.0c.txt │ └── commit_log_v1.1.txt ├── markdown │ ├── change_summary.md │ ├── commands.md │ ├── interface.md │ ├── jogging.md │ ├── laser_mode.md │ └── settings.md └── script │ ├── fit_nonlinear_spindle.py │ ├── simple_stream.py │ └── stream.py └── grbl ├── config.h ├── coolant_control.c ├── coolant_control.h ├── cpu_map.h ├── defaults.h ├── eeprom.c ├── eeprom.h ├── examples ├── grblUpload │ ├── grblUpload.ino │ └── license.txt └── grblWrite_BuildInfo │ ├── grblWrite_BuildInfo.ino │ └── license.txt ├── gcode.c ├── gcode.h ├── grbl.h ├── jog.c ├── jog.h ├── limits.c ├── limits.h ├── main.c ├── motion_control.c ├── motion_control.h ├── nuts_bolts.c ├── nuts_bolts.h ├── planner.c ├── planner.h ├── print.c ├── print.h ├── probe.c ├── probe.h ├── protocol.c ├── protocol.h ├── report.c ├── report.h ├── serial.c ├── serial.h ├── settings.c ├── settings.h ├── spindle_control.c ├── spindle_control.h ├── stepper.c ├── stepper.h ├── system.c └── system.h /.gitignore: -------------------------------------------------------------------------------- 1 | *.hex 2 | *.o 3 | *.elf 4 | *.DS_Store 5 | *.d 6 | 7 | README.md 8 | -------------------------------------------------------------------------------- /Makefile: -------------------------------------------------------------------------------- 1 | # Part of Grbl 2 | # 3 | # Copyright (c) 2009-2011 Simen Svale Skogsrud 4 | # Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC 5 | # 6 | # Grbl is free software: you can redistribute it and/or modify 7 | # it under the terms of the GNU General Public License as published by 8 | # the Free Software Foundation, either version 3 of the License, or 9 | # (at your option) any later version. 10 | # 11 | # Grbl is distributed in the hope that it will be useful, 12 | # but WITHOUT ANY WARRANTY; without even the implied warranty of 13 | # MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 14 | # GNU General Public License for more details. 15 | # 16 | # You should have received a copy of the GNU General Public License 17 | # along with Grbl. If not, see . 18 | 19 | 20 | # This is a prototype Makefile. Modify it according to your needs. 21 | # You should at least check the settings for 22 | # DEVICE ....... The AVR device you compile for 23 | # CLOCK ........ Target AVR clock rate in Hertz 24 | # OBJECTS ...... The object files created from your source files. This list is 25 | # usually the same as the list of source files with suffix ".o". 26 | # PROGRAMMER ... Options to avrdude which define the hardware you use for 27 | # uploading to the AVR and the interface where this hardware 28 | # is connected. 29 | # FUSES ........ Parameters for avrdude to flash the fuses appropriately. 30 | 31 | DEVICE ?= atmega328p 32 | CLOCK = 16000000 33 | PROGRAMMER ?= -c avrisp2 -P usb 34 | SOURCE = main.c motion_control.c gcode.c spindle_control.c coolant_control.c serial.c \ 35 | protocol.c stepper.c eeprom.c settings.c planner.c nuts_bolts.c limits.c jog.c\ 36 | print.c probe.c report.c system.c 37 | BUILDDIR = build 38 | SOURCEDIR = grbl 39 | # FUSES = -U hfuse:w:0xd9:m -U lfuse:w:0x24:m 40 | FUSES = -U hfuse:w:0xd2:m -U lfuse:w:0xff:m 41 | 42 | # Tune the lines below only if you know what you are doing: 43 | 44 | AVRDUDE = avrdude $(PROGRAMMER) -p $(DEVICE) -B 10 -F 45 | 46 | # Compile flags for avr-gcc v4.8.1. Does not produce -flto warnings. 47 | # COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections 48 | 49 | # Compile flags for avr-gcc v4.9.2 compatible with the IDE. Or if you don't care about the warnings. 50 | COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections -flto 51 | 52 | 53 | OBJECTS = $(addprefix $(BUILDDIR)/,$(notdir $(SOURCE:.c=.o))) 54 | 55 | # symbolic targets: 56 | all: grbl.hex 57 | 58 | $(BUILDDIR)/%.o: $(SOURCEDIR)/%.c 59 | $(COMPILE) -MMD -MP -c $< -o $@ 60 | 61 | .S.o: 62 | $(COMPILE) -x assembler-with-cpp -c $< -o $(BUILDDIR)/$@ 63 | # "-x assembler-with-cpp" should not be necessary since this is the default 64 | # file type for the .S (with capital S) extension. However, upper case 65 | # characters are not always preserved on Windows. To ensure WinAVR 66 | # compatibility define the file type manually. 67 | 68 | #.c.s: 69 | $(COMPILE) -S $< -o $(BUILDDIR)/$@ 70 | 71 | flash: all 72 | $(AVRDUDE) -U flash:w:grbl.hex:i 73 | 74 | fuse: 75 | $(AVRDUDE) $(FUSES) 76 | 77 | # Xcode uses the Makefile targets "", "clean" and "install" 78 | install: flash fuse 79 | 80 | # if you use a bootloader, change the command below appropriately: 81 | load: all 82 | bootloadHID grbl.hex 83 | 84 | clean: 85 | rm -f grbl.hex $(BUILDDIR)/*.o $(BUILDDIR)/*.d $(BUILDDIR)/*.elf 86 | 87 | # file targets: 88 | $(BUILDDIR)/main.elf: $(OBJECTS) 89 | $(COMPILE) -o $(BUILDDIR)/main.elf $(OBJECTS) -lm -Wl,--gc-sections 90 | 91 | grbl.hex: $(BUILDDIR)/main.elf 92 | rm -f grbl.hex 93 | avr-objcopy -j .text -j .data -O ihex $(BUILDDIR)/main.elf grbl.hex 94 | avr-size --format=berkeley $(BUILDDIR)/main.elf 95 | # If you have an EEPROM section, you must also create a hex file for the 96 | # EEPROM and add it to the "flash" target. 97 | 98 | # Targets for code debugging and analysis: 99 | disasm: main.elf 100 | avr-objdump -d $(BUILDDIR)/main.elf 101 | 102 | cpp: 103 | $(COMPILE) -E $(SOURCEDIR)/main.c 104 | 105 | # include generated header dependencies 106 | -include $(BUILDDIR)/$(OBJECTS:.o=.d) 107 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | ![GitHub Logo](https://github.com/gnea/gnea-Media/blob/master/Grbl%20Logo/Grbl%20Logo%20250px.png?raw=true) 2 | 3 | *** 4 | _Click the `Release` tab to download pre-compiled `.hex` files or just [click here](https://github.com/gnea/grbl/releases)_ 5 | *** 6 | Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. This version of Grbl runs on an Arduino with a 328p processor (Uno, Duemilanove, Nano, Micro, etc). 7 | 8 | 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. 9 | 10 | 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. 11 | 12 | Grbl includes full acceleration management with look ahead. That means the controller will look up to 16 motions into the future and plan its velocities ahead to deliver smooth acceleration and jerk-free cornering. 13 | 14 | * [Licensing](https://github.com/gnea/grbl/wiki/Licensing): Grbl is free software, released under the GPLv3 license. 15 | 16 | * For more information and help, check out our **[Wiki pages!](https://github.com/gnea/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! 17 | 18 | * Lead Developer: Sungeun "Sonny" Jeon, Ph.D. (USA) aka @chamnit 19 | 20 | * Built on the wonderful Grbl v0.6 (2011) firmware written by Simen Svale Skogsrud (Norway). 21 | 22 | *** 23 | 24 | ### Official Supporters of the Grbl CNC Project 25 | ![Official Supporters](https://github.com/gnea/gnea-Media/blob/master/Contributors.png?raw=true) 26 | 27 | 28 | *** 29 | 30 | ## Update Summary for v1.1 31 | - **IMPORTANT:** Your EEPROM will be wiped and restored with new settings. This is due to the addition of two new spindle speed '$' settings. 32 | 33 | - **Real-time Overrides** : Alters the machine running state immediately with feed, rapid, spindle speed, spindle stop, and coolant toggle controls. This awesome new feature is common only on industrial machines, often used to optimize speeds and feeds while a job is running. Most hobby CNC's try to mimic this behavior, but usually have large amounts of lag. Grbl executes overrides in realtime and within tens of milliseconds. 34 | 35 | - **Jogging Mode** : The new jogging commands are independent of the g-code parser, so that the parser state doesn't get altered and cause a potential crash if not restored properly. Documentation is included on how this works and how it can be used to control your machine via a joystick or rotary dial with a low-latency, satisfying response. 36 | 37 | - **Laser Mode** : The new "laser" mode will cause Grbl to move continuously through consecutive G1, G2, and G3 commands with spindle speed changes. When "laser" mode is disabled, Grbl will instead come to a stop to ensure a spindle comes up to speed properly. Spindle speed overrides also work with laser mode so you can tweak the laser power, if you need to during the job. Switch between "laser" mode and "normal" mode via a `$` setting. 38 | 39 | - **Dynamic Laser Power Scaling with Speed** : If your machine has low accelerations, Grbl will automagically scale the laser power based on how fast Grbl is traveling, so you won't have burnt corners when your CNC has to make a turn! Enabled by the `M4` spindle CCW command when laser mode is enabled! 40 | 41 | - **Sleep Mode** : Grbl may now be put to "sleep" via a `$SLP` command. This will disable everything, including the stepper drivers. Nice to have when you are leaving your machine unattended and want to power down everything automatically. Only a reset exits the sleep state. 42 | 43 | - **Significant Interface Improvements**: Tweaked to increase overall performance, include lots more real-time data, and to simplify maintaining and writing GUIs. Based on direct feedback from multiple GUI developers and bench performance testing. _NOTE: GUIs need to specifically update their code to be compatible with v1.1 and later._ 44 | 45 | - **New Status Reports**: To account for the additional override data, status reports have been tweaked to cram more data into it, while still being smaller than before. Documentation is included, outlining how it has been changed. 46 | - **Improved Error/Alarm Feedback** : All Grbl error and alarm messages have been changed to providing a code. Each code is associated with a specific problem, so users will know exactly what is wrong without having to guess. Documentation and an easy to parse CSV is included in the repo. 47 | - **Extended-ASCII realtime commands** : All overrides and future real-time commands are defined in the extended-ASCII character space. Unfortunately not easily type-able on a keyboard, but helps prevent accidental commands from a g-code file having these characters and gives lots of space for future expansion. 48 | - **Message Prefixes** : Every message type from Grbl has a unique prefix to help GUIs immediately determine what the message is and parse it accordingly without having to know context. The prior interface had several instances of GUIs having to figure out the meaning of a message, which made everything more complicated than it needed to be. 49 | 50 | - New OEM specific features, such as safety door parking, single configuration file build option, EEPROM restrictions and restoring controls, and storing product data information. 51 | 52 | - New safety door parking motion as a compile-option. Grbl will retract, disable the spindle/coolant, and park near Z max. When resumed, it will perform these task in reverse order and continue the program. Highly configurable, even to add more than one parking motion. See config.h for details. 53 | 54 | - New '$' Grbl settings for max and min spindle rpm. Allows for tweaking the PWM output to more closely match true spindle rpm. When max rpm is set to zero or less than min rpm, the PWM pin D11 will act like a simple enable on/off output. 55 | 56 | - Updated G28 and G30 behavior from NIST to LinuxCNC g-code description. In short, if a intermediate motion is specified, only the axes specified will move to the stored coordinates, not all axes as before. 57 | 58 | - Lots of minor bug fixes and refactoring to make the code more efficient and flexible. 59 | 60 | - **NOTE:** Arduino Mega2560 support has been moved to an active, official Grbl-Mega [project](http://www.github.com/gnea/grbl-Mega/). All new developments here and there will be synced when it makes sense to. 61 | 62 | 63 | ``` 64 | List of Supported G-Codes in Grbl v1.1: 65 | - Non-Modal Commands: G4, G10L2, G10L20, G28, G30, G28.1, G30.1, G53, G92, G92.1 66 | - Motion Modes: G0, G1, G2, G3, G38.2, G38.3, G38.4, G38.5, G80 67 | - Feed Rate Modes: G93, G94 68 | - Unit Modes: G20, G21 69 | - Distance Modes: G90, G91 70 | - Arc IJK Distance Modes: G91.1 71 | - Plane Select Modes: G17, G18, G19 72 | - Tool Length Offset Modes: G43.1, G49 73 | - Cutter Compensation Modes: G40 74 | - Coordinate System Modes: G54, G55, G56, G57, G58, G59 75 | - Control Modes: G61 76 | - Program Flow: M0, M1, M2, M30* 77 | - Coolant Control: M7*, M8, M9 78 | - Spindle Control: M3, M4, M5 79 | - Valid Non-Command Words: F, I, J, K, L, N, P, R, S, T, X, Y, Z 80 | ``` 81 | -------------------------------------------------------------------------------- /build/.gitignore: -------------------------------------------------------------------------------- 1 | # Ignore everything in this directory 2 | * 3 | # Except this file 4 | !.gitignore -------------------------------------------------------------------------------- /doc/csv/alarm_codes_en_US.csv: -------------------------------------------------------------------------------- 1 | "Alarm Code in v1.1+"," Alarm Message in v1.0-"," Alarm Description" 2 | "1","Hard limit","Hard limit has been triggered. Machine position is likely lost due to sudden halt. Re-homing is highly recommended." 3 | "2","Soft limit","Soft limit alarm. G-code motion target exceeds machine travel. Machine position retained. Alarm may be safely unlocked." 4 | "3","Abort during cycle","Reset while in motion. Machine position is likely lost due to sudden halt. Re-homing is highly recommended." 5 | "4","Probe fail","Probe fail. Probe is not in the expected initial state before starting probe cycle when G38.2 and G38.3 is not triggered and G38.4 and G38.5 is triggered." 6 | "5","Probe fail","Probe fail. Probe did not contact the workpiece within the programmed travel for G38.2 and G38.4." 7 | "6","Homing fail","Homing fail. The active homing cycle was reset." 8 | "7","Homing fail","Homing fail. Safety door was opened during homing cycle." 9 | "8","Homing fail","Homing fail. Pull off travel failed to clear limit switch. Try increasing pull-off setting or check wiring." 10 | "9","Homing fail","Homing fail. Could not find limit switch within search distances. Try increasing max travel, decreasing pull-off distance, or check wiring." 11 | "10","Homing fail","Homing fail. Second dual axis limit switch failed to trigger within configured search distance after first. Try increasing trigger fail distance or check wiring." 12 | -------------------------------------------------------------------------------- /doc/csv/build_option_codes_en_US.csv: -------------------------------------------------------------------------------- 1 | OPT: Code, Build-Option Description,State 2 | V,Variable spindle,Enabled 3 | N,Line numbers,Enabled 4 | M,Mist coolant M7,Enabled 5 | C,CoreXY,Enabled 6 | P,Parking motion,Enabled 7 | Z,Homing force origin,Enabled 8 | H,Homing single axis commands,Enabled 9 | T,Two limit switches on axis,Enabled 10 | A,Allow feed rate overrides in probe cycles,Enabled 11 | D,Use spindle direction as enable pin,Enabled 12 | 0,Spindle enable off when speed is zero,Enabled 13 | S,Software limit pin debouncing,Enabled 14 | R,Parking override control,Enabled 15 | +,Safety door input pin,Enabled 16 | *,Restore all EEPROM command,Disabled 17 | $,Restore EEPROM `$` settings command,Disabled 18 | #,Restore EEPROM parameter data command,Disabled 19 | I,Build info write user string command,Disabled 20 | E,Force sync upon EEPROM write,Disabled 21 | W,Force sync upon work coordinate offset change,Disabled 22 | L,Homing initialization auto-lock,Disabled 23 | 2,Dual axis motors,Enabled -------------------------------------------------------------------------------- /doc/csv/error_codes_en_US.csv: -------------------------------------------------------------------------------- 1 | "Error Code in v1.1+","Error Message in v1.0-","Error Description" 2 | "1","Expected command letter","G-code words consist of a letter and a value. Letter was not found." 3 | "2","Bad number format","Missing the expected G-code word value or numeric value format is not valid." 4 | "3","Invalid statement","Grbl '$' system command was not recognized or supported." 5 | "4","Value < 0","Negative value received for an expected positive value." 6 | "5","Setting disabled","Homing cycle failure. Homing is not enabled via settings." 7 | "6","Value < 3 usec","Minimum step pulse time must be greater than 3usec." 8 | "7","EEPROM read fail. Using defaults","An EEPROM read failed. Auto-restoring affected EEPROM to default values." 9 | "8","Not idle","Grbl '$' command cannot be used unless Grbl is IDLE. Ensures smooth operation during a job." 10 | "9","G-code lock","G-code commands are locked out during alarm or jog state." 11 | "10","Homing not enabled","Soft limits cannot be enabled without homing also enabled." 12 | "11","Line overflow","Max characters per line exceeded. Received command line was not executed." 13 | "12","Step rate > 30kHz","Grbl '$' setting value cause the step rate to exceed the maximum supported." 14 | "13","Check Door","Safety door detected as opened and door state initiated." 15 | "14","Line length exceeded","Build info or startup line exceeded EEPROM line length limit. Line not stored." 16 | "15","Travel exceeded","Jog target exceeds machine travel. Jog command has been ignored." 17 | "16","Invalid jog command","Jog command has no '=' or contains prohibited g-code." 18 | "17","Setting disabled","Laser mode requires PWM output." 19 | "20","Unsupported command","Unsupported or invalid g-code command found in block." 20 | "21","Modal group violation","More than one g-code command from same modal group found in block." 21 | "22","Undefined feed rate","Feed rate has not yet been set or is undefined." 22 | "23","Invalid gcode ID:23","G-code command in block requires an integer value." 23 | "24","Invalid gcode ID:24","More than one g-code command that requires axis words found in block." 24 | "25","Invalid gcode ID:25","Repeated g-code word found in block." 25 | "26","Invalid gcode ID:26","No axis words found in block for g-code command or current modal state which requires them." 26 | "27","Invalid gcode ID:27","Line number value is invalid." 27 | "28","Invalid gcode ID:28","G-code command is missing a required value word." 28 | "29","Invalid gcode ID:29","G59.x work coordinate systems are not supported." 29 | "30","Invalid gcode ID:30","G53 only allowed with G0 and G1 motion modes." 30 | "31","Invalid gcode ID:31","Axis words found in block when no command or current modal state uses them." 31 | "32","Invalid gcode ID:32","G2 and G3 arcs require at least one in-plane axis word." 32 | "33","Invalid gcode ID:33","Motion command target is invalid." 33 | "34","Invalid gcode ID:34","Arc radius value is invalid." 34 | "35","Invalid gcode ID:35","G2 and G3 arcs require at least one in-plane offset word." 35 | "36","Invalid gcode ID:36","Unused value words found in block." 36 | "37","Invalid gcode ID:37","G43.1 dynamic tool length offset is not assigned to configured tool length axis." 37 | "38","Invalid gcode ID:38","Tool number greater than max supported value." -------------------------------------------------------------------------------- /doc/csv/setting_codes_en_US.csv: -------------------------------------------------------------------------------- 1 | "$-Code"," Setting"," Units"," Setting Description" 2 | "0","Step pulse time","microseconds","Sets time length per step. Minimum 3usec." 3 | "1","Step idle delay","milliseconds","Sets a short hold delay when stopping to let dynamics settle before disabling steppers. Value 255 keeps motors enabled with no delay." 4 | "2","Step pulse invert","mask","Inverts the step signal. Set axis bit to invert (00000ZYX)." 5 | "3","Step direction invert","mask","Inverts the direction signal. Set axis bit to invert (00000ZYX)." 6 | "4","Invert step enable pin","boolean","Inverts the stepper driver enable pin signal." 7 | "5","Invert limit pins","boolean","Inverts the all of the limit input pins." 8 | "6","Invert probe pin","boolean","Inverts the probe input pin signal." 9 | "10","Status report options","mask","Alters data included in status reports." 10 | "11","Junction deviation","millimeters","Sets how fast Grbl travels through consecutive motions. Lower value slows it down." 11 | "12","Arc tolerance","millimeters","Sets the G2 and G3 arc tracing accuracy based on radial error. Beware: A very small value may effect performance." 12 | "13","Report in inches","boolean","Enables inch units when returning any position and rate value that is not a settings value." 13 | "20","Soft limits enable","boolean","Enables soft limits checks within machine travel and sets alarm when exceeded. Requires homing." 14 | "21","Hard limits enable","boolean","Enables hard limits. Immediately halts motion and throws an alarm when switch is triggered." 15 | "22","Homing cycle enable","boolean","Enables homing cycle. Requires limit switches on all axes." 16 | "23","Homing direction invert","mask","Homing searches for a switch in the positive direction. Set axis bit (00000ZYX) to search in negative direction." 17 | "24","Homing locate feed rate","mm/min","Feed rate to slowly engage limit switch to determine its location accurately." 18 | "25","Homing search seek rate","mm/min","Seek rate to quickly find the limit switch before the slower locating phase." 19 | "26","Homing switch debounce delay","milliseconds","Sets a short delay between phases of homing cycle to let a switch debounce." 20 | "27","Homing switch pull-off distance","millimeters","Retract distance after triggering switch to disengage it. Homing will fail if switch isn't cleared." 21 | "30","Maximum spindle speed","RPM","Maximum spindle speed. Sets PWM to 100% duty cycle." 22 | "31","Minimum spindle speed","RPM","Minimum spindle speed. Sets PWM to 0.4% or lowest duty cycle." 23 | "32","Laser-mode enable","boolean","Enables laser mode. Consecutive G1/2/3 commands will not halt when spindle speed is changed." 24 | "100","X-axis travel resolution","step/mm","X-axis travel resolution in steps per millimeter." 25 | "101","Y-axis travel resolution","step/mm","Y-axis travel resolution in steps per millimeter." 26 | "102","Z-axis travel resolution","step/mm","Z-axis travel resolution in steps per millimeter." 27 | "110","X-axis maximum rate","mm/min","X-axis maximum rate. Used as G0 rapid rate." 28 | "111","Y-axis maximum rate","mm/min","Y-axis maximum rate. Used as G0 rapid rate." 29 | "112","Z-axis maximum rate","mm/min","Z-axis maximum rate. Used as G0 rapid rate." 30 | "120","X-axis acceleration","mm/sec^2","X-axis acceleration. Used for motion planning to not exceed motor torque and lose steps." 31 | "121","Y-axis acceleration","mm/sec^2","Y-axis acceleration. Used for motion planning to not exceed motor torque and lose steps." 32 | "122","Z-axis acceleration","mm/sec^2","Z-axis acceleration. Used for motion planning to not exceed motor torque and lose steps." 33 | "130","X-axis maximum travel","millimeters","Maximum X-axis travel distance from homing switch. Determines valid machine space for soft-limits and homing search distances." 34 | "131","Y-axis maximum travel","millimeters","Maximum Y-axis travel distance from homing switch. Determines valid machine space for soft-limits and homing search distances." 35 | "132","Z-axis maximum travel","millimeters","Maximum Z-axis travel distance from homing switch. Determines valid machine space for soft-limits and homing search distances." 36 | -------------------------------------------------------------------------------- /doc/log/commit_log_v0.9j.txt: -------------------------------------------------------------------------------- 1 | ---------------- 2 | Date: 2015-08-14 3 | Author: Sonny Jeon 4 | Subject: Individual control pin invert compile-option. 5 | 6 | - Control pins may be individually inverted through a 7 | CONTROL_INVERT_MASK macro. This mask is define in the cpu_map.h file. 8 | 9 | 10 | ---------------- 11 | Date: 2015-07-17 12 | Author: Sonny Jeon 13 | Subject: Version bump to v0.9j 14 | 15 | - Version bump requested by OEMs to easily determine whether the 16 | firmware supports the new EEPROM reset feature. Other than that, no 17 | significant changes. 18 | -------------------------------------------------------------------------------- /doc/log/commit_log_v1.0b.txt: -------------------------------------------------------------------------------- 1 | ---------------- 2 | Date: 2015-09-30 3 | Author: Sonny Jeon 4 | Subject: Bug fixes. 5 | 6 | - G38.x was not printing correctly in the $G g-code state reports. Now 7 | fixed. 8 | 9 | - When investigating the above issue, it was noticed that G38.x 10 | wouldn’t show at all, but instead a G0 would be printed. This was 11 | unlike the v0.9j master build. It turned out volatile variables do not 12 | like to be defined inside a C struct. These are undefined on how to be 13 | handled. Once pulled out, all weird issues went away. 14 | 15 | - Also changed two ‘sizeof()’ statements in the mc_probe() and 16 | probe_state_monitor() functions to be more robust later on. 17 | 18 | - Updated the commit logs to individual files for each minor release. 19 | Forgot to update the generating script to account for this. 20 | 21 | 22 | ---------------- 23 | Date: 2015-09-30 24 | Author: Sonny Jeon 25 | Subject: Minor bug fixes. 26 | 27 | - G38.x was not printing correctly in the $G g-code state reports. Now 28 | fixed. 29 | 30 | - Potential bug regarding volatile variables inside a struct. It has 31 | never been a problem in v0.9, but ran into this during v1.0 32 | development. Just to be safe, the fixes are applied here. 33 | 34 | - Updated pre-built firmwares with these two bug fixes. 35 | 36 | 37 | ---------------- 38 | Date: 2015-09-24 39 | Author: Sonny Jeon 40 | Subject: Updated G28/G30 intermediate motion behavior. 41 | 42 | - G28 and G30’s behavior has been updated from the old NIST g-code 43 | standard to LinuxCNC’s. Previously when an intermediate motion was 44 | programmed, the NIST standard would move all axes to the final G28/30 45 | stored coordinates. LinuxCNC states it only moves the axes specified in 46 | the command. 47 | 48 | For example, suppose G28’s stored position is (x,y,z) = (1,2,3) for 49 | simplicity, and we want to do an automated z-axis tool retraction and 50 | then park at the x,y location. `G28 G91 Z5` will first move the Z axis 51 | 5mm(or inches) up, then move Z to position 3 in machine coordinates. 52 | Next, the command `G28 G91 X0 Y0` would skip the intermediate move 53 | since distance is zero, but then move only the x and y axes to machine 54 | coordinates 1 and 2, respectively. The z-axis wouldn’t move in this 55 | case, since it wasn’t specified. 56 | 57 | This change is intended to make Grbl more LinuxCNC compatible while 58 | making commands, like the shown tool retraction, much easier to 59 | implement. 60 | 61 | 62 | ---------------- 63 | Date: 2015-09-05 64 | Author: Sonny Jeon 65 | Subject: Parking motion bug fix. 66 | 67 | - Parking motion would intermittently complete the queued tool path 68 | upon resuming in certain scenarios. Now fixed. 69 | 70 | 71 | ---------------- 72 | Date: 2015-08-29 73 | Author: Sonny Jeon 74 | Subject: Optional line number reporting bug fix. 75 | 76 | - Fixed a bug where it would not compile when USE_LINE_NUMBERS was 77 | enabled. 78 | 79 | 80 | ---------------- 81 | Date: 2015-08-27 82 | Author: Sonny Jeon 83 | Subject: Update README 84 | 85 | 86 | ---------------- 87 | Date: 2015-08-27 88 | Author: Sonny Jeon 89 | Subject: v1.0 Beta Release. 90 | 91 | - Tons of new stuff in this release, which is fairly stable and well 92 | tested. However, much more is coming soon! 93 | 94 | - Real-time parking motion with safety door. When this compile option 95 | is enabled, an opened safety door will cause Grbl to automatically feed 96 | hold, retract, de-energize the spindle/coolant, and parks near Z max. 97 | After the door is closed and resume is commanded, this reverses and the 98 | program continues as if nothing happened. This is also highly 99 | configurable. See config.h for details. 100 | 101 | - New spindle max and min rpm ‘$’ settings! This has been requested 102 | often. Grbl will output 5V when commanded to turn on the spindle at its 103 | max rpm, and 0.02V with min rpm. The voltage and the rpm range are 104 | linear to each other. This should help users tweak their settings to 105 | get close to true rpm’s. 106 | 107 | - If the new max rpm ‘$’ setting is set = 0 or less than min rpm, the 108 | spindle speed PWM pin will act like a regular on/off spindle enable 109 | pin. On pin D11. 110 | 111 | - BEWARE: Your old EEPROM settings will be wiped! The new spindle rpm 112 | settings require a new settings version, so Grbl will automatically 113 | wipe and restore the EEPROM with the new defaults. 114 | 115 | - Control pin can now be inverted individually with a 116 | CONTROL_INVERT_MASK in the cpu_map header file. Not typical for users 117 | to need this, but handy to have. 118 | 119 | - Fixed bug when Grbl receive too many characters in a line and 120 | overflows. Previously it would respond with an error per overflow 121 | character and another acknowledge upon an EOL character. This broke the 122 | streaming protocol. Now fixed to only respond with an error after an 123 | EOL character. 124 | 125 | - Fixed a bug with the safety door during an ALARM mode. You now can’t 126 | home or unlock the axes until the safety door has been closed. This is 127 | for safety reasons (obviously.) 128 | 129 | - Tweaked some the Mega2560 cpu_map settings . Increased segment buffer 130 | size and fixed the spindle PWM settings to output at a higher PWM 131 | frequency. 132 | 133 | - Generalized the delay function used by G4 delay for use by parking 134 | motion. Allows non-blocking status reports and real-time control during 135 | re-energizing of the spindle and coolant. 136 | 137 | - Added spindle rpm max and min defaults to default.h files. 138 | 139 | - Added a new print float for rpm values. 140 | 141 | -------------------------------------------------------------------------------- /doc/log/commit_log_v1.0c.txt: -------------------------------------------------------------------------------- 1 | ---------------- 2 | Date: 2016-03-19 3 | Author: Sonny Jeon 4 | Subject: No variable spindle and spindle speed fix. 5 | 6 | - Soft limit errors were stuck in a feed hold without notifying the 7 | user why it was in a hold. When resumed, the soft limit error would 8 | kick in. Issue should be fixed to behave as intended to automatically 9 | hold and issue a soft limit alarm once the machine has come to a stop. 10 | 11 | 12 | ---------------- 13 | Date: 2016-03-11 14 | Author: Sonny Jeon 15 | Subject: Soft limit error bug fix. 16 | 17 | - Soft limit errors were stuck in a feed hold without notifying the 18 | user why it was in a hold. When resumed, the soft limit error would 19 | kick in. Issue should be fixed to behave as intended. To automatically 20 | hold and issue a soft limit alarm once the machine has come to a stop. 21 | 22 | 23 | ---------------- 24 | Date: 2016-03-04 25 | Author: Sonny Jeon 26 | Subject: Applied master branch bug fixes. 27 | 28 | - Planner was under-estimating maximum speeds through straight 29 | junctions in certain cases. The calculations have been updated to be 30 | more accurate. 31 | 32 | - Strange sizeof() bug in the most recent releases. Manifested as an 33 | alarm upon a power up even when homing was disabled. Fixed by declaring 34 | sizeof() with struct types, rather than variable names, even though 35 | they were validated to give the same value. 36 | 37 | - Spindle speed zero should disable the spindle. Now fixed. 38 | 39 | - New configuration option for inverting certain limit pins. Handy for 40 | mixed NO and NC switch machines. See config.h for details. 41 | 42 | 43 | ---------------- 44 | Date: 2015-11-09 45 | Author: Sonny Jeon 46 | Subject: Pin state reporting of all pins. Flash optimization. 47 | 48 | - New pin state realtime reporting feature. Instead of `Lim:000` for 49 | limit state reports, the new feature shows `Pin:000|0|0000`, or 50 | something similar. The `|` delimited fields indicate xyz limits, probe, 51 | and control pin states, where 0 is always not triggered, and 1 is 52 | triggered. Invert masks ARE accounted for. 53 | Each field may be enabled or disabled via the `$10` status report 54 | setting. The probe and control pin flags are bits 5 and 6, respectively. 55 | 56 | - Remove the now deprecated `REPORT_CONTROL_PIN_STATE` option in 57 | config.h 58 | 59 | - The old limit pin reports `Lim:000` may be re-enabled by commenting 60 | out `REPORT_ALL_PIN_STATES` in config.h. 61 | 62 | - Incremented the version letter (v1.0c) to indicate the change in 63 | reporting style. 64 | 65 | - Replaced all bit_true_atomic and bit_false_atomic macros with 66 | function calls. This saved a couple hundred bytes of flash. 67 | 68 | -------------------------------------------------------------------------------- /doc/markdown/change_summary.md: -------------------------------------------------------------------------------- 1 | ### _Grbl v1.1 - Change Summary_ 2 | 3 | -------- 4 | 5 | ### _Specific details are available in the other markdown documents._ 6 | -------- 7 | 8 | #### GUI Interface Tweaks from Grbl v0.9 9 | 10 | Grbl v1.1's interface protocol has been tweaked in the attempt to make GUI development cleaner, clearer, and hopefully easier. All messages are designed to be deterministic without needing to know the context of the message. Each can be inferred to a much greater degree than before just by the message type, which are all listed below. 11 | 12 | - `ok` / `error:x` : Normal send command and execution response acknowledgement. Used for streaming. 13 | 14 | - `< >` : Enclosed chevrons contains status report data. 15 | 16 | - `Grbl X.Xx ['$' for help]` : Welcome message indicates initialization. 17 | 18 | - `ALARM:x` : Indicates an alarm has been thrown. Grbl is now in an alarm state. 19 | 20 | - `$x=val` and `$Nx=line` indicate a settings printout from a `$` and `$N` user query, respectively. 21 | 22 | - `[MSG:]` : Indicates a non-queried feedback message. 23 | 24 | - `[GC:]` : Indicates a queried `$G` g-code state message. 25 | 26 | - `[HLP:]` : Indicates the help message. 27 | 28 | - `[G54:]`, `[G55:]`, `[G56:]`, `[G57:]`, `[G58:]`, `[G59:]`, `[G28:]`, `[G30:]`, `[G92:]`, `[TLO:]`, and `[PRB:]` messages indicate the parameter data printout from a `$#` user query. 29 | 30 | - `[VER:]` : Indicates build info and string from a `$I` user query. 31 | 32 | - `[OPT:]` : Indicates compile-time option info from a `$I` user query. 33 | 34 | - `[echo:]` : Indicates an automated line echo from a pre-parsed string prior to g-code parsing. Enabled by config.h option. 35 | 36 | - `>G54G20:ok` : The open chevron indicates startup line execution. The `:ok` suffix shows it executed correctly without adding an unmatched `ok` response on a new line. 37 | 38 | In addition, all `$x=val` settings, `error:`, and `ALARM:` messages no longer contain human-readable strings, but rather codes that are defined in other documents. The `$` help message is also reduced to just showing the available commands. Doing this saves incredible amounts of flash space. Otherwise, the new overrides features would not have fit. 39 | 40 | Other minor changes and bug fixes that may effect GUI parsing include: 41 | 42 | - Floating point values printed with zero precision do not show a decimal, or look like an integer. This includes spindle speed RPM and feed rate in mm mode. 43 | - `$G` reports fixed a long time bug with program modal state. It always showed `M0` program pause when running. Now during a normal program run, no program modal state is given until an `M0`, `M2`, or `M30` is active and then the appropriate state will be shown. 44 | 45 | On a final note, these interface tweaks came about out of necessity, because more data is being sent back from Grbl, it is capable of doing many more things, and flash space is at a premium. It's not intended to be altered again in the near future, if at all. This is likely the only and last major change to this. If you have any comments or suggestions before Grbl v1.1 goes to master, please do immediately so we can all vet the new alteration before its installed. 46 | 47 | ---- 48 | 49 | #### Realtime Status Reports Changes from Grbl v0.9 50 | 51 | - Intent of changes is to make parsing cleaner, reduce transmitting overhead without effecting overall Grbl performance, and add more feedback data, which includes three new override values and real-time velocity. 52 | 53 | - Data fields are separated by `|` pipe delimiters, rather than `,` commas that were used to separate data values. This should help with parsing. 54 | 55 | - The ability to mask and add/remove data fields from status reports via the `$10` status report mask setting has been disabled. Only selecting `MPos:` or `WPos:` coordinates is allowed. 56 | - All available data is always sent to standardize the reports across all GUIs. 57 | - For unique situations, data fields can be removed by config.h macros, but it is highly recommended to not alter these. 58 | 59 | 60 | - `MPos:` OR `WPos:` are always included in a report, but not BOTH at the same time. 61 | 62 | - This reduces transmit overhead tremendously by removing upwards to 40 characters. 63 | - `WCO:0.000,10.000,2.500` A current work coordinate offset is now sent to easily convert between position vectors, where `WPos = MPos - WCO` for each axis. 64 | - `WCO:` is included immediately whenever a `WCO:` value changes or intermittently after every **X** status reports as a refresh. Refresh rates can dynamically vary from 10 to 30 (configurable) reports depending on what Grbl is doing. 65 | - `WCO:` is simply the sum of the work coordinate system, G92, and G43.1 tool length offsets. 66 | - Basically, a GUI just needs to retain the last `WCO:` and apply the equation to get the other position vector. 67 | - `WCO:` messages may only be disabled via a config.h compile-option, if a GUI wants to handle the work position calculations on its own to free up more transmit bandwidth. 68 | - Be aware of the following issue regarding `WPos:`. 69 | - In Grbl v0.9 and prior, there is an old outstanding bug where the `WPos:` work position reported may not correlate to what is executing, because `WPos:` is based on the g-code parser state, which can be several motions behind. Grbl v1.1 now forces the planner buffer to empty, sync, and stops motion whenever there is a command that alters the work coordinate offsets `G10,G43.1,G92,G54-59`. This is the simplest way to ensure `WPos:` is always correct. Fortunately, it's exceedingly rare that any of these commands are used need continuous motions through them. 70 | - A compile-time option is available to disable the planner sync and forced stop, but, if used, it's up to the GUI to handle this position correlation issue. 71 | 72 | 73 | - The `Hold` and `Door` states includes useful sub-state info via a `:` colon delimiter and an integer value. See descriptions for details. 74 | 75 | - Limit and other input pin reports have significantly changed to reduce transmit overhead. 76 | - The data type description is now just `Pn:`, rather than `Lim:000` or `Pin:000|0|0000` 77 | - It does not appear if no inputs are detected as triggered. 78 | - If an input is triggered, ```Pn:``` will be followed by a letter or set of letters of every triggered input pin. `XYZPDHRS` for the XYZ-axes limits, Probe, Door, Hold, soft-Reset, cycle Start pins, respectively. 79 | - For example, a triggered Z-limit and probe pin would report `Pn:ZP`. 80 | 81 | 82 | - Buffer data (planner and serial RX) reports have been tweaked and combined. 83 | 84 | - `Bf:15,128`. The first value is the available blocks in the planner buffer and the second is available bytes in the serial RX buffer. 85 | - Note that this is different than before, where it reported blocks/bytes "in-use", rather than "available". This change does not require a GUI to know how many blocks/bytes Grbl has been compiled with, which can be substantially different on a Grbl-Mega build. 86 | 87 | 88 | - Override reports are intermittent since they don't change often once set. 89 | 90 | - Overrides are included in every 10 or 20 status reports (configurable) depending on what Grbl is doing or, if an override value or toggle state changes, automatically in the next report. 91 | - There are two override fields: 92 | - `Ov:100,100,100` Organized as feed, rapid, and spindle speed overrides in percent. 93 | 94 | - Accessory states are shown alongside override reports when they are active. Like pin states, an accessory state report `A:SFM` contains a letter indicating an active accessory. Letters `S`, `C`, `F`, and `M` are defined as spindle CW, spindle CCW, flood coolant, and mist coolant, respectively. The pins are directly polled and shown here. 95 | 96 | - Line numbers, when enabled in config.h, are omitted when: 97 | 98 | - No line number is passed to Grbl in a block. 99 | - Grbl is performing a system motion like homing, jogging, or parking. 100 | - Grbl is executing g-code block that does not contain a motion, like `G20G54` or `G4P1` dwell. (NOTE: Looking to fixing this later.) 101 | 102 | ------- 103 | 104 | #### New Commands 105 | 106 | - `$SLP` - Grbl v1.1 now has a sleep mode that can be invoked by this command. It requires Grbl to be in either an IDLE or ALARM state. Once invoked, Grbl will de-energize all connected systems, including the spindle, coolant, and stepper drivers. It'll enter a suspend state that can only be exited by a reset. When reset, Grbl will re-initiatize in an ALARM state because the steppers were disabled and position can not be guaranteed. 107 | - NOTE: Grbl-Mega can invoke the sleep mode at any time, when the sleep timeout feature is enabled in config.h. It does so when Grbl has not received any external input after a timeout period. 108 | 109 | - `$J=line` New jogging commands. This command behaves much like a normal G1 command, but there are some key differences. Jog commands don't alter the g-code parser state, meaning a GUI doesn't have to manage it anymore. Jog commands may be queued and cancelled at any time, where they are automatically flushed from the planner buffer without requiring a reset. See the jogging documentation on how they work and how they may be used to implement a low-latency joystick or rotary dial. 110 | 111 | - Laser mode `$` setting - When enabled, laser mode will move through consecutive G1, G2, and G3 motion commands that have different spindle speed values without stopping. A spindle speed of zero will disable the laser without stopping as well. However, when spindle states change, like M3 or M5, stops are still enforced. 112 | - NOTE: Parking motions are automatically disabled when laser mode is enabled to prevent burning. 113 | 114 | - `G56 P1` and `G56 P0` - When enabled in config.h with Grbl's parking motion, these commands enable and disable, respectively, the parking motion. Like all override control commands, these commands are modal and are part of the g-code stream. -------------------------------------------------------------------------------- /doc/markdown/jogging.md: -------------------------------------------------------------------------------- 1 | # Grbl v1.1 Jogging 2 | 3 | This document outlines how to use Grbl v1.1's new jogging commands. These command differ because they can be cancelled and all queued motions are automatically purged with a simple jog-cancel or feed hold real-time command. Jogging command do not alter the g-code parser state in any way, so you no longer have to worry if you remembered to set the distance mode back to `G90` prior to starting a job. Also, jogging works well with an analog joysticks and rotary dials! See the implementation notes below. 4 | 5 | ## How to Use 6 | Executing a jog requires a specific command structure, as described below: 7 | 8 | - The first three characters must be '$J=' to indicate the jog. 9 | - The jog command follows immediate after the '=' and works like a normal G1 command. 10 | - Feed rate is only interpreted in G94 units per minute. A prior G93 state is ignored during jog. 11 | - Required words: 12 | - XYZ: One or more axis words with target value. 13 | - F - Feed rate value. NOTE: Each jog requires this value and is not treated as modal. 14 | - Optional words: Jog executes based on current G20/G21 and G90/G91 g-code parser state. If one of the following optional words is passed, that state is overridden for one command only. 15 | - G20 or G21 - Inch and millimeter mode 16 | - G90 or G91 - Absolute and incremental distances 17 | - G53 - Move in machine coordinates 18 | - N line numbers are valid. Will show in reports, if enabled, but is otherwise ignored. 19 | - All other g-codes, m-codes, and value words (including S and T) are not accepted in the jog command. 20 | - Spaces and comments are allowed in the command. These are removed by the pre-parser. 21 | 22 | - Example: G21 and G90 are active modal states prior to jogging. These are sequential commands. 23 | - `$J=X10.0 Y-1.5` will move to X=10.0mm and Y=-1.5mm in work coordinate frame (WPos). 24 | - `$J=G91 G20 X0.5` will move +0.5 inches (12.7mm) to X=22.7mm (WPos). Note that G91 and G20 are only applied to this jog command. 25 | - `$J=G53 Y5.0` will move the machine to Y=5.0mm in the machine coordinate frame (MPos). If the work coordinate offset for the y-axis is 2.0mm, then Y is 3.0mm in (WPos). 26 | 27 | Jog commands behave almost identically to normal g-code streaming. Every jog command will 28 | return an 'ok' when the jogging motion has been parsed and is setup for execution. If a 29 | command is not valid, Grbl will return an 'error:'. Multiple jogging commands may be 30 | queued in sequence. 31 | 32 | The main differences are: 33 | 34 | - During a jog, Grbl will report a 'Jog' state while executing the jog. 35 | - A jog command will only be accepted when Grbl is in either the 'Idle' or 'Jog' states. 36 | - Jogging motions may not be mixed with g-code commands while executing, which will return a lockout error, if attempted. 37 | - All jogging motion(s) may be cancelled at anytime with a simple jog cancel realtime command or a feed hold or safety door event. Grbl will automatically flush Grbl's internal buffers of any queued jogging motions and return to the 'Idle' state. No soft-reset required. 38 | - If soft-limits are enabled, jog commands that exceed the machine travel simply does not execute the command and return an error, rather than throwing an alarm in normal operation. 39 | - IMPORTANT: Jogging does not alter the g-code parser state. Hence, no g-code modes need to be explicitly managed, unlike previous ways of implementing jogs with commands like 'G91G1X1F100'. Since G91, G1, and F feed rates are modal and if they are not changed back prior to resuming/starting a job, a job may not run how its was intended and result in a crash. 40 | 41 | ------ 42 | 43 | ## Joystick Implementation 44 | 45 | Jogging in Grbl v1.1 is generally intended to address some prior issues with old bootstrapped jogging methods. Unfortunately, the new Grbl jogging is not a complete solution. Flash and memory restrictions prevent the original envisioned implementation, but most of these can be mimicked by the following suggested methodology. 46 | 47 | With a combination of the new jog cancel and moving in `G91` incremental mode, the following implementation can create low latency feel for an analog joystick or similar control device. 48 | 49 | - Basic Implementation Overview: 50 | - Create a loop to read the joystick signal and translate it to a desired jog motion vector. 51 | - Send Grbl a very short `G91` incremental distance jog command with a feed rate based on the joystick throw. 52 | - Wait for an 'ok' acknowledgement before restarting the loop. 53 | - Continually read the joystick input and send Grbl short jog motions to keep Grbl's planner buffer full. 54 | - If the joystick is returned to its neutral position, stop the jog loop and simply send Grbl a jog cancel real-time command. This will stop motion immediately somewhere along the programmed jog path with virtually zero-latency and automatically flush Grbl's planner queue. It's not advised to use a feed hold to cancel a jog, as it can lead to inadvertently suspending Grbl if its sent after returning to the IDLE state. 55 | 56 | 57 | The overall idea is to minimize the total distance in the planner queue to provide a low-latency feel to joystick control. The main trick is ensuring there is just enough distance in the planner queue, such that the programmed feed rate is always met. How to compute this will be explain later. In practice, most machines will have a 0.5-1.0 second latency. When combined with the immediate jog cancel command, joystick interaction can be quite enjoyable and satisfying. 58 | 59 | However, please note, if a machine has a low acceleration and is being asked to move at a high programmed feed rate, joystick latency can get up to a handful of seconds. It may sound bad, but this is how long it'll take for a low acceleration machine, traveling at a high feed rate, to slow down to a stop. The argument can be made for a low acceleration machine that you really shouldn't be jogging at a high feed rate. It is difficult for a user to gauge where the machine will come to a stop. You risk overshooting your target destination, which can result in an expensive or dangerous crash. 60 | 61 | One of the advantages of this approach is that a GUI can deterministically track where Grbl will go by the jog commands it has already sent to Grbl. As long as a jog isn't cancelled, every jog command is guaranteed to execute. In the event a jog cancel is invoked, the GUI would just need to refresh their internal position from a status report after Grbl has cleared planner buffer and returned to the IDLE (or DOOR, if ajar) state from the JOG state. This stopped position will always be somewhere along the programmed jog path. If desired, jogging can then be quickly and easily restarted with a new tracked path. 62 | 63 | In combination with `G53` move in machine coordinates, a GUI can restrict jogging from moving into "keep-out" zones inside the machine space. This can be very useful for avoiding crashing into delicate probing hardware, workholding mechanisms, or other fixed features inside machine space that you want to avoid. 64 | 65 | #### How to compute incremental distances 66 | 67 | The quickest and easiest way to determine what the length of a jog motion needs to be to minimize latency are defined by the following equations. 68 | 69 | `s = v * dt` - Computes distance traveled for next jog command. 70 | 71 | where: 72 | 73 | - `s` - Incremental distance of jog command. 74 | - `dt` - Estimated execution time of a single jog command in seconds. 75 | - `v` - Current jog feed rate in **mm/sec**, not mm/min. Less than or equal to max jog rate. 76 | - `N` - Number of Grbl planner blocks (`N=15`) 77 | - `T = dt * N` - Computes total estimated latency in seconds. 78 | 79 | The time increment `dt` may be defined to whatever value you need. Obviously, you'd like the lowest value, since that translates to lower overall latency `T`. However, it is constrained by two factors. 80 | 81 | - `dt > 10ms` - The time it takes Grbl to parse and plan one jog command and receive the next one. Depending on a lot of factors, this can be around 1 to 5 ms. To be conservative, `10ms` is used. Keep in mind that on some systems, this value may still be greater than `10ms` due to round-trip communication latency. 82 | 83 | - `dt > v^2 / (2 * a * (N-1))` - The time increment needs to be large enough to ensure the jog feed rate will be acheived. Grbl always plans to a stop over the total distance queued in the planner buffer. This is primarily to ensure the machine will safely stop if a disconnection occurs. This equation simply ensures that `dt` is big enough to satisfy this constraint. 84 | 85 | - For simplicity, use the max jog feed rate for `v` in mm/sec and the smallest acceleration setting between the jog axes being moved in mm/sec^2. 86 | 87 | - For a lower latency, `dt` can be computed for each jog motion, where `v` is the current rate and `a` is the max acceleration along the jog vector. This is very useful if traveling a very slow speeds to locate a part zero. The `v` rate would be much lower in this scenario and the total latency would decrease quadratically. 88 | 89 | In practice, most CNC machines will operate with a jogging time increment of `0.025 sec` < `dt` < `0.06 sec`, which translates to about a `0.4` to `0.9` second total latency when traveling at the max jog rate. Good enough for most people. 90 | 91 | However, if jogging at a slower speed and a GUI adjusts the `dt` with it, you can get very close to the 0.1 second response time by human-interface guidelines for "feeling instantaneous". Not too shabby! 92 | 93 | With some ingenuity, this jogging methodology may be applied to different devices such as a rotary dial or touchscreen. An "inertial-feel", like swipe-scrolling on a smartphone or tablet, can be simulated by managing the jog rate decay and sending Grbl the associated jog commands. While this jogging implementation requires more initial work by a GUI, it is also inherently more flexible because you have complete deterministic control of how jogging behaves. -------------------------------------------------------------------------------- /doc/markdown/laser_mode.md: -------------------------------------------------------------------------------- 1 | ## Grbl v1.1 Laser Mode 2 | 3 | **_DISCLAIMER: Lasers are extremely dangerous devices. They can instantly cause fires and permanently damage your vision. Please read and understand all related documentation for your laser prior to using it. The Grbl project is not resposible for any damage or issues the firmware may cause, as defined by its GPL license._** 4 | 5 | ---- 6 | 7 | Outlined in this document is how Grbl alters its running conditions for the new laser mode to provide both improved performance and attempting to enforce some basic user safety precautions. 8 | 9 | ## Laser Mode Overview 10 | 11 | The main difference between default Grbl operation and the laser mode is how the spindle/laser output is controlled with motions involved. Every time a spindle state `M3 M4 M5` or spindle speed `Sxxx` is altered, Grbl would come to a stop, allow the spindle to change, and then continue. This is the normal operating procedure for a milling machine spindle. It needs time to change speeds. 12 | 13 | However, if a laser starts and stops like this for every spindle change, this leads to scorching and uneven cutting/engraving! Grbl's new laser mode prevents unnecessary stops whenever possible and adds a new dynamic laser power mode that automagically scales power based on current speed related to programmed rate. So, you can get super clean and crisp results, even on a low-acceleration machine! 14 | 15 | Enabling or disabling Grbl's laser mode is easy. Just alter the **$32** Grbl setting. 16 | - **To Enable**: Send Grbl a `$32=1` command. 17 | - **To Disable:** Send Grbl a `$32=0` command. 18 | 19 | **WARNING:** If you switch back from laser mode to a spindle for milling, you **MUST** disable laser mode by sending Grbl a `$32=0` command. Milling operations require the spindle to get up to the right rpm to cut correctly and to be **safe**, helping to prevent a tool from breaking and flinging metal shards everywhere. With laser mode disabled, Grbl will briefly pause upon any spindle speed or state change to give the spindle a chance to get up to speed before continuing. 20 | 21 | 22 | ## Laser Mode Operation 23 | 24 | When laser mode is enabled, Grbl controls laser power by varying the **0-5V** voltage from the spindle PWM D11 pin. **0V** should be treated as disabled, while **5V** is full power. Intermediate output voltages are also assumed to be linear with laser power, such that **2.5V** is approximate 50% laser power. (A compile time option exists to shift this linear model to start at a non-zero voltage.) 25 | 26 | By default, the spindle PWM frequency is **1kHz**, which is the recommended PWM frequency for most current Grbl-compatible lasers system. If a different frequency is required, this may be altered by editing the `cpu_map.h` file. 27 | 28 | The laser is enabled with the `M3` spindle CW and `M4` spindle CCW commands. These enable two different laser modes that are advantageous for different reasons each. 29 | 30 | - **`M3` Constant Laser Power Mode:** 31 | 32 | - Constant laser power mode simply keeps the laser power as programmed, regardless if the machine is moving, accelerating, or stopped. This provides better control of the laser state. With a good G-code program, this can lead to more consistent cuts in more difficult materials. 33 | 34 | - For a clean cut and prevent scorching with `M3` constant power mode, it's a good idea to add lead-in and lead-out motions around the line you want to cut to give some space for the machine to accelerate and decelerate. 35 | 36 | - NOTE: `M3` can be used to keep the laser on for focusing. 37 | 38 | - **`M4` Dynamic Laser Power Mode:** 39 | - Dynamic laser power mode will automatically adjust laser power based on the current speed relative to the programmed rate. It essentially ensures the amount of laser energy along a cut is consistent even though the machine may be stopped or actively accelerating. This is very useful for clean, precise engraving and cutting on simple materials across a large range of G-code generation methods by CAM programs. It will generally run faster and may be all you need to use. 40 | 41 | - Grbl calculates laser power based on the assumption that laser power is linear with speed and the material. Often, this is not the case. Lasers can cut differently at varying power levels and some materials may not cut well at a particular speed and/power. In short, this means that dynamic power mode may not work for all situations. Always do a test piece prior to using this with a new material or machine. 42 | 43 | - When not in motion, `M4` dynamic mode turns off the laser. It only turns on when the machine moves. This generally makes the laser safer to operate, because, unlike `M3`, it will never burn a hole through your table, if you stop and forget to turn `M3` off in time. 44 | 45 | Describe below are the operational changes to Grbl when laser mode is enabled. Please read these carefully and understand them fully, because nothing is worse than a garage _**fire**_. 46 | 47 | - Grbl will move continuously through **consecutive** motion commands when programmed with a new `S` spindle speed (laser power). The spindle PWM pin will be updated instantaneously through each motion without stopping. 48 | - Example: The following set of g-code commands will not pause between each of them when laser mode is enabled, but will pause when disabled. 49 | 50 | ``` 51 | G1 X10 S100 F50 52 | G1 X0 S90 53 | G2 X0 I5 S80 54 | ``` 55 | - Grbl will enforce a laser mode motion stop in a few circumstances. Primarily to ensure alterations stay in sync with the g-code program. 56 | 57 | - Any `M3`, `M4`, `M5` spindle state _change_. 58 | - `M3` only and no motion programmed: A `S` spindle speed _change_. 59 | - `M3` only and no motion programmed: A `G1 G2 G3` laser powered state _change_ to `G0 G80` laser disabled state. 60 | - NOTE: `M4` does not stop for anything but a spindle state _change_. 61 | 62 | - The laser will only turn on when Grbl is in a `G1`, `G2`, or `G3` motion mode. 63 | 64 | - In other words, a `G0` rapid motion mode or `G38.x` probe cycle will never turn on and always disable the laser, but will still update the running modal state. When changed to a `G1 G2 G3` modal state, Grbl will immediately enable the laser based on the current running state. 65 | 66 | - Please remember that `G0` is the default motion mode upon power up and reset. You will need to alter it to `G1`, `G2`, or `G3` if you want to manually turn on your laser. This is strictly a safety measure. 67 | 68 | - Example: `G0 M3 S1000` will not turn on the laser, but will set the laser modal state to `M3` enabled and power of `S1000`. A following `G1` command will then immediately be set to `M3` and `S1000`. 69 | 70 | - To have the laser powered during a jog motion, first enable a valid motion mode and spindle state. The following jog motions will inherit and maintain the previous laser state. Please use with caution though. This ability is primarily to allow turning on the laser on a _very low_ power to use the laser dot to jog and visibly locate the start position of a job. 71 | 72 | 73 | - An `S0` spindle speed of zero will turn off the laser. When programmed with a valid laser motion, Grbl will disable the laser instantaneously without stopping for the duration of that motion and future motions until set greater than zero.. 74 | 75 | - `M3` constant laser mode, this is a great way to turn off the laser power while continuously moving between a `G1` laser motion and a `G0` rapid motion without having to stop. Program a short `G1 S0` motion right before the `G0` motion and a `G1 Sxxx` motion is commanded right after to go back to cutting. 76 | 77 | 78 | ----- 79 | ###CAM Developer Implementation Notes 80 | 81 | TODO: Add some suggestions on how to write laser G-code for Grbl. 82 | 83 | - When using `M3` constant laser power mode, try to avoid force-sync conditions during a job whenever possible. Basically every spindle speed change must be accompanied by a valid motion. Any motion is fine, since Grbl will automatically enable and disable the laser based on the modal state. Avoid a `G0` and `G1` command with no axis words in this mode and in the middle of a job. 84 | 85 | - Ensure smooth motions throughout by turning the laser on and off without an `M3 M4 M5` spindle state command. There are two ways to do this: 86 | 87 | - _Program a zero spindle speed `S0`_: `S0` is valid G-code and turns off the spindle/laser without changing the spindle state. In laser mode, Grbl will smoothly move through consecutive motions and turn off the spindle. Conversely, you can turn on the laser with a spindle speed `S` greater than zero. Remember that `M3` constant power mode requires any spindle speed `S` change to be programmed with a motion to allow continuous motion, while `M4` dynamic power mode does not. 88 | 89 | - _Program an unpowered motion between powered motions_: If you are traversing between parts of a raster job that don't need to have the laser powered, program a `G0` rapid between them. `G0` enforces the laser to be disabled automatically. The last spindle speed programmed doesn't change, so if a valid powered motion, like a `G1` is executed after, it'll immediately re-power the laser with the last programmed spindle speed when executing that motion. 90 | -------------------------------------------------------------------------------- /doc/script/simple_stream.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | """\ 3 | Simple g-code streaming script for grbl 4 | 5 | Provided as an illustration of the basic communication interface 6 | for grbl. When grbl has finished parsing the g-code block, it will 7 | return an 'ok' or 'error' response. When the planner buffer is full, 8 | grbl will not send a response until the planner buffer clears space. 9 | 10 | G02/03 arcs are special exceptions, where they inject short line 11 | segments directly into the planner. So there may not be a response 12 | from grbl for the duration of the arc. 13 | 14 | --------------------- 15 | The MIT License (MIT) 16 | 17 | Copyright (c) 2012 Sungeun K. Jeon 18 | 19 | Permission is hereby granted, free of charge, to any person obtaining a copy 20 | of this software and associated documentation files (the "Software"), to deal 21 | in the Software without restriction, including without limitation the rights 22 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 23 | copies of the Software, and to permit persons to whom the Software is 24 | furnished to do so, subject to the following conditions: 25 | 26 | The above copyright notice and this permission notice shall be included in 27 | all copies or substantial portions of the Software. 28 | 29 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 30 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 31 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 32 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 33 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 34 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 35 | THE SOFTWARE. 36 | --------------------- 37 | """ 38 | 39 | import serial 40 | import time 41 | 42 | # Open grbl serial port 43 | s = serial.Serial('/dev/tty.usbmodem1811',115200) 44 | 45 | # Open g-code file 46 | f = open('grbl.gcode','r'); 47 | 48 | # Wake up grbl 49 | s.write("\r\n\r\n") 50 | time.sleep(2) # Wait for grbl to initialize 51 | s.flushInput() # Flush startup text in serial input 52 | 53 | # Stream g-code to grbl 54 | for line in f: 55 | l = line.strip() # Strip all EOL characters for consistency 56 | print 'Sending: ' + l, 57 | s.write(l + '\n') # Send g-code block to grbl 58 | grbl_out = s.readline() # Wait for grbl response with carriage return 59 | print ' : ' + grbl_out.strip() 60 | 61 | # Wait here until grbl is finished to close serial port and file. 62 | raw_input(" Press to exit and disable grbl.") 63 | 64 | # Close file and serial port 65 | f.close() 66 | s.close() -------------------------------------------------------------------------------- /doc/script/stream.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python 2 | """\ 3 | 4 | Stream g-code to grbl controller 5 | 6 | This script differs from the simple_stream.py script by 7 | tracking the number of characters in grbl's serial read 8 | buffer. This allows grbl to fetch the next line directly 9 | from the serial buffer and does not have to wait for a 10 | response from the computer. This effectively adds another 11 | buffer layer to prevent buffer starvation. 12 | 13 | CHANGELOG: 14 | - 20170531: Status report feedback at 1.0 second intervals. 15 | Configurable baudrate and report intervals. Bug fixes. 16 | - 20161212: Added push message feedback for simple streaming 17 | - 20140714: Updated baud rate to 115200. Added a settings 18 | write mode via simple streaming method. MIT-licensed. 19 | 20 | TODO: 21 | - Add realtime control commands during streaming. 22 | 23 | --------------------- 24 | The MIT License (MIT) 25 | 26 | Copyright (c) 2012-2017 Sungeun K. Jeon 27 | 28 | Permission is hereby granted, free of charge, to any person obtaining a copy 29 | of this software and associated documentation files (the "Software"), to deal 30 | in the Software without restriction, including without limitation the rights 31 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 32 | copies of the Software, and to permit persons to whom the Software is 33 | furnished to do so, subject to the following conditions: 34 | 35 | The above copyright notice and this permission notice shall be included in 36 | all copies or substantial portions of the Software. 37 | 38 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 39 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 40 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 41 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 42 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 43 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 44 | THE SOFTWARE. 45 | --------------------- 46 | """ 47 | 48 | import serial 49 | import re 50 | import time 51 | import sys 52 | import argparse 53 | import threading 54 | 55 | RX_BUFFER_SIZE = 128 56 | BAUD_RATE = 115200 57 | ENABLE_STATUS_REPORTS = True 58 | REPORT_INTERVAL = 1.0 # seconds 59 | 60 | is_run = True # Controls query timer 61 | 62 | # Define command line argument interface 63 | parser = argparse.ArgumentParser(description='Stream g-code file to grbl. (pySerial and argparse libraries required)') 64 | parser.add_argument('gcode_file', type=argparse.FileType('r'), 65 | help='g-code filename to be streamed') 66 | parser.add_argument('device_file', 67 | help='serial device path') 68 | parser.add_argument('-q','--quiet',action='store_true', default=False, 69 | help='suppress output text') 70 | parser.add_argument('-s','--settings',action='store_true', default=False, 71 | help='settings write mode') 72 | parser.add_argument('-c','--check',action='store_true', default=False, 73 | help='stream in check mode') 74 | args = parser.parse_args() 75 | 76 | # Periodic timer to query for status reports 77 | # TODO: Need to track down why this doesn't restart consistently before a release. 78 | def send_status_query(): 79 | s.write('?') 80 | 81 | def periodic_timer() : 82 | while is_run: 83 | send_status_query() 84 | time.sleep(REPORT_INTERVAL) 85 | 86 | 87 | # Initialize 88 | s = serial.Serial(args.device_file,BAUD_RATE) 89 | f = args.gcode_file 90 | verbose = True 91 | if args.quiet : verbose = False 92 | settings_mode = False 93 | if args.settings : settings_mode = True 94 | check_mode = False 95 | if args.check : check_mode = True 96 | 97 | # Wake up grbl 98 | print "Initializing Grbl..." 99 | s.write("\r\n\r\n") 100 | 101 | # Wait for grbl to initialize and flush startup text in serial input 102 | time.sleep(2) 103 | s.flushInput() 104 | 105 | if check_mode : 106 | print "Enabling Grbl Check-Mode: SND: [$C]", 107 | s.write("$C\n") 108 | while 1: 109 | grbl_out = s.readline().strip() # Wait for grbl response with carriage return 110 | if grbl_out.find('error') >= 0 : 111 | print "REC:",grbl_out 112 | print " Failed to set Grbl check-mode. Aborting..." 113 | quit() 114 | elif grbl_out.find('ok') >= 0 : 115 | if verbose: print 'REC:',grbl_out 116 | break 117 | 118 | start_time = time.time(); 119 | 120 | # Start status report periodic timer 121 | if ENABLE_STATUS_REPORTS : 122 | timerThread = threading.Thread(target=periodic_timer) 123 | timerThread.daemon = True 124 | timerThread.start() 125 | 126 | # Stream g-code to grbl 127 | l_count = 0 128 | error_count = 0 129 | if settings_mode: 130 | # Send settings file via simple call-response streaming method. Settings must be streamed 131 | # in this manner since the EEPROM accessing cycles shut-off the serial interrupt. 132 | print "SETTINGS MODE: Streaming", args.gcode_file.name, " to ", args.device_file 133 | for line in f: 134 | l_count += 1 # Iterate line counter 135 | # l_block = re.sub('\s|\(.*?\)','',line).upper() # Strip comments/spaces/new line and capitalize 136 | l_block = line.strip() # Strip all EOL characters for consistency 137 | if verbose: print "SND>"+str(l_count)+": \"" + l_block + "\"" 138 | s.write(l_block + '\n') # Send g-code block to grbl 139 | while 1: 140 | grbl_out = s.readline().strip() # Wait for grbl response with carriage return 141 | if grbl_out.find('ok') >= 0 : 142 | if verbose: print " REC<"+str(l_count)+": \""+grbl_out+"\"" 143 | break 144 | elif grbl_out.find('error') >= 0 : 145 | if verbose: print " REC<"+str(l_count)+": \""+grbl_out+"\"" 146 | error_count += 1 147 | break 148 | else: 149 | print " MSG: \""+grbl_out+"\"" 150 | else: 151 | # Send g-code program via a more agressive streaming protocol that forces characters into 152 | # Grbl's serial read buffer to ensure Grbl has immediate access to the next g-code command 153 | # rather than wait for the call-response serial protocol to finish. This is done by careful 154 | # counting of the number of characters sent by the streamer to Grbl and tracking Grbl's 155 | # responses, such that we never overflow Grbl's serial read buffer. 156 | g_count = 0 157 | c_line = [] 158 | for line in f: 159 | l_count += 1 # Iterate line counter 160 | l_block = re.sub('\s|\(.*?\)','',line).upper() # Strip comments/spaces/new line and capitalize 161 | # l_block = line.strip() 162 | c_line.append(len(l_block)+1) # Track number of characters in grbl serial read buffer 163 | grbl_out = '' 164 | while sum(c_line) >= RX_BUFFER_SIZE-1 | s.inWaiting() : 165 | out_temp = s.readline().strip() # Wait for grbl response 166 | if out_temp.find('ok') < 0 and out_temp.find('error') < 0 : 167 | print " MSG: \""+out_temp+"\"" # Debug response 168 | else : 169 | if out_temp.find('error') >= 0 : error_count += 1 170 | g_count += 1 # Iterate g-code counter 171 | if verbose: print " REC<"+str(g_count)+": \""+out_temp+"\"" 172 | del c_line[0] # Delete the block character count corresponding to the last 'ok' 173 | s.write(l_block + '\n') # Send g-code block to grbl 174 | if verbose: print "SND>"+str(l_count)+": \"" + l_block + "\"" 175 | # Wait until all responses have been received. 176 | while l_count > g_count : 177 | out_temp = s.readline().strip() # Wait for grbl response 178 | if out_temp.find('ok') < 0 and out_temp.find('error') < 0 : 179 | print " MSG: \""+out_temp+"\"" # Debug response 180 | else : 181 | if out_temp.find('error') >= 0 : error_count += 1 182 | g_count += 1 # Iterate g-code counter 183 | del c_line[0] # Delete the block character count corresponding to the last 'ok' 184 | if verbose: print " REC<"+str(g_count)+": \""+out_temp + "\"" 185 | 186 | # Wait for user input after streaming is completed 187 | print "\nG-code streaming finished!" 188 | end_time = time.time(); 189 | is_run = False; 190 | print " Time elapsed: ",end_time-start_time,"\n" 191 | if check_mode : 192 | if error_count > 0 : 193 | print "CHECK FAILED:",error_count,"errors found! See output for details.\n" 194 | else : 195 | print "CHECK PASSED: No errors found in g-code program.\n" 196 | else : 197 | print "WARNING: Wait until Grbl completes buffered g-code blocks before exiting." 198 | raw_input(" Press to exit and disable Grbl.") 199 | 200 | # Close file and serial port 201 | f.close() 202 | s.close() 203 | -------------------------------------------------------------------------------- /grbl/coolant_control.c: -------------------------------------------------------------------------------- 1 | /* 2 | coolant_control.c - coolant control methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #include "grbl.h" 22 | 23 | 24 | void coolant_init() 25 | { 26 | COOLANT_FLOOD_DDR |= (1 << COOLANT_FLOOD_BIT); // Configure as output pin 27 | #ifdef ENABLE_M7 28 | COOLANT_MIST_DDR |= (1 << COOLANT_MIST_BIT); 29 | #endif 30 | coolant_stop(); 31 | } 32 | 33 | 34 | // Returns current coolant output state. Overrides may alter it from programmed state. 35 | uint8_t coolant_get_state() 36 | { 37 | uint8_t cl_state = COOLANT_STATE_DISABLE; 38 | #ifdef INVERT_COOLANT_FLOOD_PIN 39 | if (bit_isfalse(COOLANT_FLOOD_PORT,(1 << COOLANT_FLOOD_BIT))) { 40 | #else 41 | if (bit_istrue(COOLANT_FLOOD_PORT,(1 << COOLANT_FLOOD_BIT))) { 42 | #endif 43 | cl_state |= COOLANT_STATE_FLOOD; 44 | } 45 | #ifdef ENABLE_M7 46 | #ifdef INVERT_COOLANT_MIST_PIN 47 | if (bit_isfalse(COOLANT_MIST_PORT,(1 << COOLANT_MIST_BIT))) { 48 | #else 49 | if (bit_istrue(COOLANT_MIST_PORT,(1 << COOLANT_MIST_BIT))) { 50 | #endif 51 | cl_state |= COOLANT_STATE_MIST; 52 | } 53 | #endif 54 | return(cl_state); 55 | } 56 | 57 | 58 | // Directly called by coolant_init(), coolant_set_state(), and mc_reset(), which can be at 59 | // an interrupt-level. No report flag set, but only called by routines that don't need it. 60 | void coolant_stop() 61 | { 62 | #ifdef INVERT_COOLANT_FLOOD_PIN 63 | COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT); 64 | #else 65 | COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT); 66 | #endif 67 | #ifdef ENABLE_M7 68 | #ifdef INVERT_COOLANT_MIST_PIN 69 | COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT); 70 | #else 71 | COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT); 72 | #endif 73 | #endif 74 | } 75 | 76 | 77 | // Main program only. Immediately sets flood coolant running state and also mist coolant, 78 | // if enabled. Also sets a flag to report an update to a coolant state. 79 | // Called by coolant toggle override, parking restore, parking retract, sleep mode, g-code 80 | // parser program end, and g-code parser coolant_sync(). 81 | void coolant_set_state(uint8_t mode) 82 | { 83 | if (sys.abort) { return; } // Block during abort. 84 | 85 | if (mode & COOLANT_FLOOD_ENABLE) { 86 | #ifdef INVERT_COOLANT_FLOOD_PIN 87 | COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT); 88 | #else 89 | COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT); 90 | #endif 91 | } else { 92 | #ifdef INVERT_COOLANT_FLOOD_PIN 93 | COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT); 94 | #else 95 | COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT); 96 | #endif 97 | } 98 | 99 | #ifdef ENABLE_M7 100 | if (mode & COOLANT_MIST_ENABLE) { 101 | #ifdef INVERT_COOLANT_MIST_PIN 102 | COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT); 103 | #else 104 | COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT); 105 | #endif 106 | } else { 107 | #ifdef INVERT_COOLANT_MIST_PIN 108 | COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT); 109 | #else 110 | COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT); 111 | #endif 112 | } 113 | #endif 114 | 115 | sys.report_ovr_counter = 0; // Set to report change immediately 116 | } 117 | 118 | 119 | // G-code parser entry-point for setting coolant state. Forces a planner buffer sync and bails 120 | // if an abort or check-mode is active. 121 | void coolant_sync(uint8_t mode) 122 | { 123 | if (sys.state == STATE_CHECK_MODE) { return; } 124 | protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program. 125 | coolant_set_state(mode); 126 | } 127 | -------------------------------------------------------------------------------- /grbl/coolant_control.h: -------------------------------------------------------------------------------- 1 | /* 2 | coolant_control.h - spindle control methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #ifndef coolant_control_h 22 | #define coolant_control_h 23 | 24 | #define COOLANT_NO_SYNC false 25 | #define COOLANT_FORCE_SYNC true 26 | 27 | #define COOLANT_STATE_DISABLE 0 // Must be zero 28 | #define COOLANT_STATE_FLOOD PL_COND_FLAG_COOLANT_FLOOD 29 | #define COOLANT_STATE_MIST PL_COND_FLAG_COOLANT_MIST 30 | 31 | 32 | // Initializes coolant control pins. 33 | void coolant_init(); 34 | 35 | // Returns current coolant output state. Overrides may alter it from programmed state. 36 | uint8_t coolant_get_state(); 37 | 38 | // Immediately disables coolant pins. 39 | void coolant_stop(); 40 | 41 | // Sets the coolant pins according to state specified. 42 | void coolant_set_state(uint8_t mode); 43 | 44 | // G-code parser entry-point for setting coolant states. Checks for and executes additional conditions. 45 | void coolant_sync(uint8_t mode); 46 | 47 | #endif 48 | -------------------------------------------------------------------------------- /grbl/cpu_map.h: -------------------------------------------------------------------------------- 1 | /* 2 | cpu_map.h - CPU and pin mapping configuration file 3 | Part of Grbl 4 | 5 | Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | /* The cpu_map.h files serve as a central pin mapping selection file for different 22 | processor types or alternative pin layouts. This version of Grbl officially supports 23 | only the Arduino Mega328p. */ 24 | 25 | 26 | #ifndef cpu_map_h 27 | #define cpu_map_h 28 | 29 | 30 | #ifdef CPU_MAP_ATMEGA328P // (Arduino Uno) Officially supported by Grbl. 31 | 32 | // Define serial port pins and interrupt vectors. 33 | #define SERIAL_RX USART_RX_vect 34 | #define SERIAL_UDRE USART_UDRE_vect 35 | 36 | // Define step pulse output pins. NOTE: All step bit pins must be on the same port. 37 | #define STEP_DDR DDRD 38 | #define STEP_PORT PORTD 39 | #define X_STEP_BIT 2 // Uno Digital Pin 2 40 | #define Y_STEP_BIT 3 // Uno Digital Pin 3 41 | #define Z_STEP_BIT 4 // Uno Digital Pin 4 42 | #define STEP_MASK ((1< 62.5kHz 145 | // #define SPINDLE_TCCRB_INIT_MASK (1< 7.8kHz (Used in v0.9) 146 | // #define SPINDLE_TCCRB_INIT_MASK ((1< 1.96kHz 147 | #define SPINDLE_TCCRB_INIT_MASK (1< 0.98kHz (J-tech laser) 148 | 149 | // NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings. 150 | #define SPINDLE_PWM_DDR DDRB 151 | #define SPINDLE_PWM_PORT PORTB 152 | #define SPINDLE_PWM_BIT 3 // Uno Digital Pin 11 153 | 154 | #else 155 | 156 | // Dual axis feature requires an independent step pulse pin to operate. The independent direction pin is not 157 | // absolutely necessary but facilitates easy direction inverting with a Grbl $$ setting. These pins replace 158 | // the spindle direction and optional coolant mist pins. 159 | 160 | #ifdef DUAL_AXIS_CONFIG_PROTONEER_V3_51 161 | // NOTE: Step pulse and direction pins may be on any port and output pin. 162 | #define STEP_DDR_DUAL DDRC 163 | #define STEP_PORT_DUAL PORTC 164 | #define DUAL_STEP_BIT 4 // Uno Analog Pin 4 165 | #define STEP_MASK_DUAL ((1< 62.5kHz 209 | // #define SPINDLE_TCCRB_INIT_MASK (1< 7.8kHz (Used in v0.9) 210 | // #define SPINDLE_TCCRB_INIT_MASK ((1< 1.96kHz 211 | #define SPINDLE_TCCRB_INIT_MASK (1< 0.98kHz (J-tech laser) 212 | 213 | // NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings. 214 | #define SPINDLE_PWM_DDR DDRB 215 | #define SPINDLE_PWM_PORT PORTB 216 | #define SPINDLE_PWM_BIT 3 // Uno Digital Pin 11 217 | #endif 218 | 219 | // NOTE: Variable spindle not supported with this shield. 220 | #ifdef DUAL_AXIS_CONFIG_CNC_SHIELD_CLONE 221 | // NOTE: Step pulse and direction pins may be on any port and output pin. 222 | #define STEP_DDR_DUAL DDRB 223 | #define STEP_PORT_DUAL PORTB 224 | #define DUAL_STEP_BIT 4 // Uno Digital Pin 12 225 | #define STEP_MASK_DUAL ((1< 25 | #include 26 | 27 | /* These EEPROM bits have different names on different devices. */ 28 | #ifndef EEPE 29 | #define EEPE EEWE //!< EEPROM program/write enable. 30 | #define EEMPE EEMWE //!< EEPROM master program/write enable. 31 | #endif 32 | 33 | /* These two are unfortunately not defined in the device include files. */ 34 | #define EEPM1 5 //!< EEPROM Programming Mode Bit 1. 35 | #define EEPM0 4 //!< EEPROM Programming Mode Bit 0. 36 | 37 | /* Define to reduce code size. */ 38 | #define EEPROM_IGNORE_SELFPROG //!< Remove SPM flag polling. 39 | 40 | /*! \brief Read byte from EEPROM. 41 | * 42 | * This function reads one byte from a given EEPROM address. 43 | * 44 | * \note The CPU is halted for 4 clock cycles during EEPROM read. 45 | * 46 | * \param addr EEPROM address to read from. 47 | * \return The byte read from the EEPROM address. 48 | */ 49 | unsigned char eeprom_get_char( unsigned int addr ) 50 | { 51 | do {} while( EECR & (1< 0; size--) { 133 | checksum = (checksum << 1) || (checksum >> 7); 134 | checksum += *source; 135 | eeprom_put_char(destination++, *(source++)); 136 | } 137 | eeprom_put_char(destination, checksum); 138 | } 139 | 140 | int memcpy_from_eeprom_with_checksum(char *destination, unsigned int source, unsigned int size) { 141 | unsigned char data, checksum = 0; 142 | for(; size > 0; size--) { 143 | data = eeprom_get_char(source++); 144 | checksum = (checksum << 1) || (checksum >> 7); 145 | checksum += data; 146 | *(destination++) = data; 147 | } 148 | return(checksum == eeprom_get_char(source)); 149 | } 150 | 151 | // end of file 152 | -------------------------------------------------------------------------------- /grbl/eeprom.h: -------------------------------------------------------------------------------- 1 | /* 2 | eeprom.h - EEPROM methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2009-2011 Simen Svale Skogsrud 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #ifndef eeprom_h 22 | #define eeprom_h 23 | 24 | unsigned char eeprom_get_char(unsigned int addr); 25 | void eeprom_put_char(unsigned int addr, unsigned char new_value); 26 | void memcpy_to_eeprom_with_checksum(unsigned int destination, char *source, unsigned int size); 27 | int memcpy_from_eeprom_with_checksum(char *destination, unsigned int source, unsigned int size); 28 | 29 | #endif 30 | -------------------------------------------------------------------------------- /grbl/examples/grblUpload/grblUpload.ino: -------------------------------------------------------------------------------- 1 | /*********************************************************************** 2 | This sketch compiles and uploads Grbl to your 328p-based Arduino! 3 | 4 | To use: 5 | - First make sure you have imported Grbl source code into your Arduino 6 | IDE. There are details on our Github website on how to do this. 7 | 8 | - Select your Arduino Board and Serial Port in the Tools drop-down menu. 9 | NOTE: Grbl only officially supports 328p-based Arduinos, like the Uno. 10 | Using other boards will likely not work! 11 | 12 | - Then just click 'Upload'. That's it! 13 | 14 | For advanced users: 15 | If you'd like to see what else Grbl can do, there are some additional 16 | options for customization and features you can enable or disable. 17 | Navigate your file system to where the Arduino IDE has stored the Grbl 18 | source code files, open the 'config.h' file in your favorite text 19 | editor. Inside are dozens of feature descriptions and #defines. Simply 20 | comment or uncomment the #defines or alter their assigned values, save 21 | your changes, and then click 'Upload' here. 22 | 23 | Copyright (c) 2015 Sungeun K. Jeon 24 | Released under the MIT-license. See license.txt for details. 25 | ***********************************************************************/ 26 | 27 | #include 28 | 29 | // Do not alter this file! 30 | -------------------------------------------------------------------------------- /grbl/examples/grblUpload/license.txt: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2015 Sungeun K. Jeon 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in 13 | all copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 21 | THE SOFTWARE. -------------------------------------------------------------------------------- /grbl/examples/grblWrite_BuildInfo/grblWrite_BuildInfo.ino: -------------------------------------------------------------------------------- 1 | /*********************************************************************** 2 | This sketch writes a `$I` build info string directly into Arduino EEPROM 3 | 4 | To use: 5 | - Just alter the "build_info_line" string to whatever you'd like. Then 6 | compile and upload this sketch to your Arduino. 7 | 8 | - If your Arduino is blinking slowly, your string has already been 9 | written to your EEPROM and been verified by checksums! That's it! 10 | 11 | - If you Arduino LED is blinking fast, something went wrong and the 12 | checksums don't match. You can optionally connect to the Arduino via 13 | the serial monitor, and the sketch will show what its doing. 14 | 15 | NOTE: This sketch is provided as a tool template for OEMs who may need 16 | to restrict users from altering their build info, so they can place 17 | important product information here when enabling the restriction. 18 | 19 | NOTE: When uploading Grbl to the Arduino with this sketch on it, make 20 | sure you see the slow blink before you start the upload process. This 21 | ensures you aren't flashing Grbl when it's in mid-write of the EEPROM. 22 | 23 | Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC 24 | Released under the MIT-license. See license.txt for details. 25 | ***********************************************************************/ 26 | 27 | #include 28 | #include 29 | 30 | #define SERIAL_BAUD_RATE 115200 31 | #define LINE_LENGTH 80U // Grbl line length 32 | #define BYTE_LOCATION 942U // Grbl build info EEPROM address. 33 | 34 | 35 | // ----- CHANGE THIS LINE ----- 36 | 37 | char build_info_line[LINE_LENGTH] = "Testing123."; 38 | 39 | // ----------------------------- 40 | 41 | 42 | uint8_t status = false; 43 | int ledPin = 13; // LED connected to digital pin 13 44 | 45 | void setup() { 46 | Serial.begin(SERIAL_BAUD_RATE); 47 | delay(500); 48 | 49 | uint32_t address = BYTE_LOCATION; 50 | uint32_t size = LINE_LENGTH; 51 | char *write_pointer = (char*)build_info_line; 52 | uint8_t write_checksum = 0; 53 | for (; size>0; size--) { 54 | write_checksum = (write_checksum << 1) || (write_checksum >> 7); 55 | write_checksum += *write_pointer; 56 | EEPROM.put(address++, *(write_pointer++)); 57 | } 58 | EEPROM.put(address,write_checksum); 59 | 60 | Serial.print(F("-> Writing line to EEPROM: '")); 61 | Serial.print(build_info_line); 62 | Serial.print(F("'\n\r-> Write checksum: ")); 63 | Serial.println(write_checksum,DEC); 64 | 65 | size = LINE_LENGTH; 66 | address = BYTE_LOCATION; 67 | uint8_t data = 0; 68 | char read_line[LINE_LENGTH]; 69 | char *read_pointer = (char*)read_line; 70 | uint8_t read_checksum = 0; 71 | uint8_t stored_checksum = 0; 72 | for(; size > 0; size--) { 73 | data = EEPROM.read(address++); 74 | read_checksum = (read_checksum << 1) || (read_checksum >> 7); 75 | read_checksum += data; 76 | *(read_pointer++) = data; 77 | } 78 | stored_checksum = EEPROM.read(address); 79 | 80 | Serial.print(F("<- Reading line from EEPROM: '")); 81 | Serial.print(read_line); 82 | Serial.print("'\n\r<- Read checksum: "); 83 | Serial.println(read_checksum,DEC); 84 | 85 | if ((read_checksum == write_checksum) && (read_checksum == stored_checksum)) { 86 | status = true; 87 | Serial.print(F("SUCCESS! All checksums match!\r\n")); 88 | } else { 89 | if (write_checksum != stored_checksum) { 90 | Serial.println(F("ERROR! Write and stored EEPROM checksums don't match!")); 91 | } else { 92 | Serial.println(F("ERROR! Read and stored checksums don't match!")); 93 | } 94 | } 95 | pinMode(ledPin, OUTPUT); // sets the digital pin as output 96 | } 97 | 98 | void loop() { 99 | // Blink to let user know EEPROM write status. 100 | // Slow blink is 'ok'. Fast blink is an 'error'. 101 | digitalWrite(ledPin, HIGH); // sets the LED on 102 | if (status) { delay(1500); } // Slow blink 103 | else { delay(100); } // Rapid blink 104 | digitalWrite(ledPin, LOW); // sets the LED off 105 | if (status) { delay(1500); } 106 | else { delay(100); } 107 | } 108 | 109 | 110 | -------------------------------------------------------------------------------- /grbl/examples/grblWrite_BuildInfo/license.txt: -------------------------------------------------------------------------------- 1 | The MIT License (MIT) 2 | 3 | Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in 13 | all copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 21 | THE SOFTWARE. -------------------------------------------------------------------------------- /grbl/gcode.h: -------------------------------------------------------------------------------- 1 | /* 2 | gcode.h - rs274/ngc parser. 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef gcode_h 23 | #define gcode_h 24 | 25 | 26 | // Define modal group internal numbers for checking multiple command violations and tracking the 27 | // type of command that is called in the block. A modal group is a group of g-code commands that are 28 | // mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute 29 | // a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online, 30 | // and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc). 31 | // NOTE: Modal group define values must be sequential and starting from zero. 32 | #define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal 33 | #define MODAL_GROUP_G1 1 // [G0,G1,G2,G3,G38.2,G38.3,G38.4,G38.5,G80] Motion 34 | #define MODAL_GROUP_G2 2 // [G17,G18,G19] Plane selection 35 | #define MODAL_GROUP_G3 3 // [G90,G91] Distance mode 36 | #define MODAL_GROUP_G4 4 // [G91.1] Arc IJK distance mode 37 | #define MODAL_GROUP_G5 5 // [G93,G94] Feed rate mode 38 | #define MODAL_GROUP_G6 6 // [G20,G21] Units 39 | #define MODAL_GROUP_G7 7 // [G40] Cutter radius compensation mode. G41/42 NOT SUPPORTED. 40 | #define MODAL_GROUP_G8 8 // [G43.1,G49] Tool length offset 41 | #define MODAL_GROUP_G12 9 // [G54,G55,G56,G57,G58,G59] Coordinate system selection 42 | #define MODAL_GROUP_G13 10 // [G61] Control mode 43 | 44 | #define MODAL_GROUP_M4 11 // [M0,M1,M2,M30] Stopping 45 | #define MODAL_GROUP_M7 12 // [M3,M4,M5] Spindle turning 46 | #define MODAL_GROUP_M8 13 // [M7,M8,M9] Coolant control 47 | #define MODAL_GROUP_M9 14 // [M56] Override control 48 | 49 | // Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used 50 | // internally by the parser to know which command to execute. 51 | // NOTE: Some macro values are assigned specific values to make g-code state reporting and parsing 52 | // compile a litte smaller. Necessary due to being completely out of flash on the 328p. Although not 53 | // ideal, just be careful with values that state 'do not alter' and check both report.c and gcode.c 54 | // to see how they are used, if you need to alter them. 55 | 56 | // Modal Group G0: Non-modal actions 57 | #define NON_MODAL_NO_ACTION 0 // (Default: Must be zero) 58 | #define NON_MODAL_DWELL 4 // G4 (Do not alter value) 59 | #define NON_MODAL_SET_COORDINATE_DATA 10 // G10 (Do not alter value) 60 | #define NON_MODAL_GO_HOME_0 28 // G28 (Do not alter value) 61 | #define NON_MODAL_SET_HOME_0 38 // G28.1 (Do not alter value) 62 | #define NON_MODAL_GO_HOME_1 30 // G30 (Do not alter value) 63 | #define NON_MODAL_SET_HOME_1 40 // G30.1 (Do not alter value) 64 | #define NON_MODAL_ABSOLUTE_OVERRIDE 53 // G53 (Do not alter value) 65 | #define NON_MODAL_SET_COORDINATE_OFFSET 92 // G92 (Do not alter value) 66 | #define NON_MODAL_RESET_COORDINATE_OFFSET 102 //G92.1 (Do not alter value) 67 | 68 | // Modal Group G1: Motion modes 69 | #define MOTION_MODE_SEEK 0 // G0 (Default: Must be zero) 70 | #define MOTION_MODE_LINEAR 1 // G1 (Do not alter value) 71 | #define MOTION_MODE_CW_ARC 2 // G2 (Do not alter value) 72 | #define MOTION_MODE_CCW_ARC 3 // G3 (Do not alter value) 73 | #define MOTION_MODE_PROBE_TOWARD 140 // G38.2 (Do not alter value) 74 | #define MOTION_MODE_PROBE_TOWARD_NO_ERROR 141 // G38.3 (Do not alter value) 75 | #define MOTION_MODE_PROBE_AWAY 142 // G38.4 (Do not alter value) 76 | #define MOTION_MODE_PROBE_AWAY_NO_ERROR 143 // G38.5 (Do not alter value) 77 | #define MOTION_MODE_NONE 80 // G80 (Do not alter value) 78 | 79 | // Modal Group G2: Plane select 80 | #define PLANE_SELECT_XY 0 // G17 (Default: Must be zero) 81 | #define PLANE_SELECT_ZX 1 // G18 (Do not alter value) 82 | #define PLANE_SELECT_YZ 2 // G19 (Do not alter value) 83 | 84 | // Modal Group G3: Distance mode 85 | #define DISTANCE_MODE_ABSOLUTE 0 // G90 (Default: Must be zero) 86 | #define DISTANCE_MODE_INCREMENTAL 1 // G91 (Do not alter value) 87 | 88 | // Modal Group G4: Arc IJK distance mode 89 | #define DISTANCE_ARC_MODE_INCREMENTAL 0 // G91.1 (Default: Must be zero) 90 | 91 | // Modal Group M4: Program flow 92 | #define PROGRAM_FLOW_RUNNING 0 // (Default: Must be zero) 93 | #define PROGRAM_FLOW_PAUSED 3 // M0 94 | #define PROGRAM_FLOW_OPTIONAL_STOP 1 // M1 NOTE: Not supported, but valid and ignored. 95 | #define PROGRAM_FLOW_COMPLETED_M2 2 // M2 (Do not alter value) 96 | #define PROGRAM_FLOW_COMPLETED_M30 30 // M30 (Do not alter value) 97 | 98 | // Modal Group G5: Feed rate mode 99 | #define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero) 100 | #define FEED_RATE_MODE_INVERSE_TIME 1 // G93 (Do not alter value) 101 | 102 | // Modal Group G6: Units mode 103 | #define UNITS_MODE_MM 0 // G21 (Default: Must be zero) 104 | #define UNITS_MODE_INCHES 1 // G20 (Do not alter value) 105 | 106 | // Modal Group G7: Cutter radius compensation mode 107 | #define CUTTER_COMP_DISABLE 0 // G40 (Default: Must be zero) 108 | 109 | // Modal Group G13: Control mode 110 | #define CONTROL_MODE_EXACT_PATH 0 // G61 (Default: Must be zero) 111 | 112 | // Modal Group M7: Spindle control 113 | #define SPINDLE_DISABLE 0 // M5 (Default: Must be zero) 114 | #define SPINDLE_ENABLE_CW PL_COND_FLAG_SPINDLE_CW // M3 (NOTE: Uses planner condition bit flag) 115 | #define SPINDLE_ENABLE_CCW PL_COND_FLAG_SPINDLE_CCW // M4 (NOTE: Uses planner condition bit flag) 116 | 117 | // Modal Group M8: Coolant control 118 | #define COOLANT_DISABLE 0 // M9 (Default: Must be zero) 119 | #define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag) 120 | #define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag) 121 | 122 | // Modal Group G8: Tool length offset 123 | #define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero) 124 | #define TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC 1 // G43.1 125 | 126 | // Modal Group M9: Override control 127 | #ifdef DEACTIVATE_PARKING_UPON_INIT 128 | #define OVERRIDE_DISABLED 0 // (Default: Must be zero) 129 | #define OVERRIDE_PARKING_MOTION 1 // M56 130 | #else 131 | #define OVERRIDE_PARKING_MOTION 0 // M56 (Default: Must be zero) 132 | #define OVERRIDE_DISABLED 1 // Parking disabled. 133 | #endif 134 | 135 | // Modal Group G12: Active work coordinate system 136 | // N/A: Stores coordinate system value (54-59) to change to. 137 | 138 | // Define parameter word mapping. 139 | #define WORD_F 0 140 | #define WORD_I 1 141 | #define WORD_J 2 142 | #define WORD_K 3 143 | #define WORD_L 4 144 | #define WORD_N 5 145 | #define WORD_P 6 146 | #define WORD_R 7 147 | #define WORD_S 8 148 | #define WORD_T 9 149 | #define WORD_X 10 150 | #define WORD_Y 11 151 | #define WORD_Z 12 152 | 153 | // Define g-code parser position updating flags 154 | #define GC_UPDATE_POS_TARGET 0 // Must be zero 155 | #define GC_UPDATE_POS_SYSTEM 1 156 | #define GC_UPDATE_POS_NONE 2 157 | 158 | // Define probe cycle exit states and assign proper position updating. 159 | #define GC_PROBE_FOUND GC_UPDATE_POS_SYSTEM 160 | #define GC_PROBE_ABORT GC_UPDATE_POS_NONE 161 | #define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE 162 | #define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET 163 | #ifdef SET_CHECK_MODE_PROBE_TO_START 164 | #define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE 165 | #else 166 | #define GC_PROBE_CHECK_MODE GC_UPDATE_POS_TARGET 167 | #endif 168 | 169 | // Define gcode parser flags for handling special cases. 170 | #define GC_PARSER_NONE 0 // Must be zero. 171 | #define GC_PARSER_JOG_MOTION bit(0) 172 | #define GC_PARSER_CHECK_MANTISSA bit(1) 173 | #define GC_PARSER_ARC_IS_CLOCKWISE bit(2) 174 | #define GC_PARSER_PROBE_IS_AWAY bit(3) 175 | #define GC_PARSER_PROBE_IS_NO_ERROR bit(4) 176 | #define GC_PARSER_LASER_FORCE_SYNC bit(5) 177 | #define GC_PARSER_LASER_DISABLE bit(6) 178 | #define GC_PARSER_LASER_ISMOTION bit(7) 179 | 180 | 181 | // NOTE: When this struct is zeroed, the above defines set the defaults for the system. 182 | typedef struct { 183 | uint8_t motion; // {G0,G1,G2,G3,G38.2,G80} 184 | uint8_t feed_rate; // {G93,G94} 185 | uint8_t units; // {G20,G21} 186 | uint8_t distance; // {G90,G91} 187 | // uint8_t distance_arc; // {G91.1} NOTE: Don't track. Only default supported. 188 | uint8_t plane_select; // {G17,G18,G19} 189 | // uint8_t cutter_comp; // {G40} NOTE: Don't track. Only default supported. 190 | uint8_t tool_length; // {G43.1,G49} 191 | uint8_t coord_select; // {G54,G55,G56,G57,G58,G59} 192 | // uint8_t control; // {G61} NOTE: Don't track. Only default supported. 193 | uint8_t program_flow; // {M0,M1,M2,M30} 194 | uint8_t coolant; // {M7,M8,M9} 195 | uint8_t spindle; // {M3,M4,M5} 196 | uint8_t override; // {M56} 197 | } gc_modal_t; 198 | 199 | typedef struct { 200 | float f; // Feed 201 | float ijk[3]; // I,J,K Axis arc offsets 202 | uint8_t l; // G10 or canned cycles parameters 203 | int32_t n; // Line number 204 | float p; // G10 or dwell parameters 205 | // float q; // G82 peck drilling 206 | float r; // Arc radius 207 | float s; // Spindle speed 208 | uint8_t t; // Tool selection 209 | float xyz[3]; // X,Y,Z Translational axes 210 | } gc_values_t; 211 | 212 | 213 | typedef struct { 214 | gc_modal_t modal; 215 | 216 | float spindle_speed; // RPM 217 | float feed_rate; // Millimeters/min 218 | uint8_t tool; // Tracks tool number. NOT USED. 219 | int32_t line_number; // Last line number sent 220 | 221 | float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code 222 | 223 | float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine 224 | // position in mm. Loaded from EEPROM when called. 225 | float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to 226 | // machine zero in mm. Non-persistent. Cleared upon reset and boot. 227 | float tool_length_offset; // Tracks tool length offset value when enabled. 228 | } parser_state_t; 229 | extern parser_state_t gc_state; 230 | 231 | 232 | typedef struct { 233 | uint8_t non_modal_command; 234 | gc_modal_t modal; 235 | gc_values_t values; 236 | } parser_block_t; 237 | 238 | 239 | // Initialize the parser 240 | void gc_init(); 241 | 242 | // Execute one block of rs275/ngc/g-code 243 | uint8_t gc_execute_line(char *line); 244 | 245 | // Set g-code parser position. Input in steps. 246 | void gc_sync_position(); 247 | 248 | #endif 249 | -------------------------------------------------------------------------------- /grbl/grbl.h: -------------------------------------------------------------------------------- 1 | /* 2 | grbl.h - main Grbl include file 3 | Part of Grbl 4 | 5 | Copyright (c) 2015-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #ifndef grbl_h 22 | #define grbl_h 23 | 24 | // Grbl versioning system 25 | #define GRBL_VERSION "1.1h" 26 | #define GRBL_VERSION_BUILD "20190830" 27 | 28 | // Define standard libraries used by Grbl. 29 | #include 30 | #include 31 | #include 32 | #include 33 | #include 34 | #include 35 | #include 36 | #include 37 | #include 38 | #include 39 | #include 40 | 41 | // Define the Grbl system include files. NOTE: Do not alter organization. 42 | #include "config.h" 43 | #include "nuts_bolts.h" 44 | #include "settings.h" 45 | #include "system.h" 46 | #include "defaults.h" 47 | #include "cpu_map.h" 48 | #include "planner.h" 49 | #include "coolant_control.h" 50 | #include "eeprom.h" 51 | #include "gcode.h" 52 | #include "limits.h" 53 | #include "motion_control.h" 54 | #include "planner.h" 55 | #include "print.h" 56 | #include "probe.h" 57 | #include "protocol.h" 58 | #include "report.h" 59 | #include "serial.h" 60 | #include "spindle_control.h" 61 | #include "stepper.h" 62 | #include "jog.h" 63 | 64 | // --------------------------------------------------------------------------------------- 65 | // COMPILE-TIME ERROR CHECKING OF DEFINE VALUES: 66 | 67 | #ifndef HOMING_CYCLE_0 68 | #error "Required HOMING_CYCLE_0 not defined." 69 | #endif 70 | 71 | #if defined(USE_SPINDLE_DIR_AS_ENABLE_PIN) && !defined(VARIABLE_SPINDLE) 72 | #error "USE_SPINDLE_DIR_AS_ENABLE_PIN may only be used with VARIABLE_SPINDLE enabled" 73 | #endif 74 | 75 | #if defined(USE_SPINDLE_DIR_AS_ENABLE_PIN) && !defined(CPU_MAP_ATMEGA328P) 76 | #error "USE_SPINDLE_DIR_AS_ENABLE_PIN may only be used with a 328p processor" 77 | #endif 78 | 79 | #if !defined(USE_SPINDLE_DIR_AS_ENABLE_PIN) && defined(SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED) 80 | #error "SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED may only be used with USE_SPINDLE_DIR_AS_ENABLE_PIN enabled" 81 | #endif 82 | 83 | #if defined(PARKING_ENABLE) 84 | #if defined(HOMING_FORCE_SET_ORIGIN) 85 | #error "HOMING_FORCE_SET_ORIGIN is not supported with PARKING_ENABLE at this time." 86 | #endif 87 | #endif 88 | 89 | #if defined(ENABLE_PARKING_OVERRIDE_CONTROL) 90 | #if !defined(PARKING_ENABLE) 91 | #error "ENABLE_PARKING_OVERRIDE_CONTROL must be enabled with PARKING_ENABLE." 92 | #endif 93 | #endif 94 | 95 | #if defined(SPINDLE_PWM_MIN_VALUE) 96 | #if !(SPINDLE_PWM_MIN_VALUE > 0) 97 | #error "SPINDLE_PWM_MIN_VALUE must be greater than zero." 98 | #endif 99 | #endif 100 | 101 | #if (REPORT_WCO_REFRESH_BUSY_COUNT < REPORT_WCO_REFRESH_IDLE_COUNT) 102 | #error "WCO busy refresh is less than idle refresh." 103 | #endif 104 | #if (REPORT_OVR_REFRESH_BUSY_COUNT < REPORT_OVR_REFRESH_IDLE_COUNT) 105 | #error "Override busy refresh is less than idle refresh." 106 | #endif 107 | #if (REPORT_WCO_REFRESH_IDLE_COUNT < 2) 108 | #error "WCO refresh must be greater than one." 109 | #endif 110 | #if (REPORT_OVR_REFRESH_IDLE_COUNT < 1) 111 | #error "Override refresh must be greater than zero." 112 | #endif 113 | 114 | #if defined(ENABLE_DUAL_AXIS) 115 | #if !((DUAL_AXIS_SELECT == X_AXIS) || (DUAL_AXIS_SELECT == Y_AXIS)) 116 | #error "Dual axis currently supports X or Y axes only." 117 | #endif 118 | #if defined(DUAL_AXIS_CONFIG_CNC_SHIELD_CLONE) && defined(VARIABLE_SPINDLE) 119 | #error "VARIABLE_SPINDLE not supported with DUAL_AXIS_CNC_SHIELD_CLONE." 120 | #endif 121 | #if defined(DUAL_AXIS_CONFIG_CNC_SHIELD_CLONE) && defined(DUAL_AXIS_CONFIG_PROTONEER_V3_51) 122 | #error "More than one dual axis configuration found. Select one." 123 | #endif 124 | #if !defined(DUAL_AXIS_CONFIG_CNC_SHIELD_CLONE) && !defined(DUAL_AXIS_CONFIG_PROTONEER_V3_51) 125 | #error "No supported dual axis configuration found. Select one." 126 | #endif 127 | #if defined(COREXY) 128 | #error "CORE XY not supported with dual axis feature." 129 | #endif 130 | #if defined(USE_SPINDLE_DIR_AS_ENABLE_PIN) 131 | #error "USE_SPINDLE_DIR_AS_ENABLE_PIN not supported with dual axis feature." 132 | #endif 133 | #if defined(ENABLE_M7) 134 | #error "ENABLE_M7 not supported with dual axis feature." 135 | #endif 136 | #endif 137 | 138 | // --------------------------------------------------------------------------------------- 139 | 140 | #endif 141 | -------------------------------------------------------------------------------- /grbl/jog.c: -------------------------------------------------------------------------------- 1 | /* 2 | jog.h - Jogging methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #include "grbl.h" 22 | 23 | 24 | // Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog. 25 | uint8_t jog_execute(plan_line_data_t *pl_data, parser_block_t *gc_block) 26 | { 27 | // Initialize planner data struct for jogging motions. 28 | // NOTE: Spindle and coolant are allowed to fully function with overrides during a jog. 29 | pl_data->feed_rate = gc_block->values.f; 30 | pl_data->condition |= PL_COND_FLAG_NO_FEED_OVERRIDE; 31 | #ifdef USE_LINE_NUMBERS 32 | pl_data->line_number = gc_block->values.n; 33 | #endif 34 | 35 | if (bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)) { 36 | if (system_check_travel_limits(gc_block->values.xyz)) { return(STATUS_TRAVEL_EXCEEDED); } 37 | } 38 | 39 | // Valid jog command. Plan, set state, and execute. 40 | mc_line(gc_block->values.xyz,pl_data); 41 | if (sys.state == STATE_IDLE) { 42 | if (plan_get_current_block() != NULL) { // Check if there is a block to execute. 43 | sys.state = STATE_JOG; 44 | st_prep_buffer(); 45 | st_wake_up(); // NOTE: Manual start. No state machine required. 46 | } 47 | } 48 | 49 | return(STATUS_OK); 50 | } 51 | -------------------------------------------------------------------------------- /grbl/jog.h: -------------------------------------------------------------------------------- 1 | /* 2 | jog.h - Jogging methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #ifndef jog_h 22 | #define jog_h 23 | 24 | #include "gcode.h" 25 | 26 | // System motion line numbers must be zero. 27 | #define JOG_LINE_NUMBER 0 28 | 29 | // Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog. 30 | uint8_t jog_execute(plan_line_data_t *pl_data, parser_block_t *gc_block); 31 | 32 | #endif 33 | -------------------------------------------------------------------------------- /grbl/limits.h: -------------------------------------------------------------------------------- 1 | /* 2 | limits.h - code pertaining to limit-switches and performing the homing cycle 3 | Part of Grbl 4 | 5 | Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef limits_h 23 | #define limits_h 24 | 25 | 26 | // Initialize the limits module 27 | void limits_init(); 28 | 29 | // Disables hard limits. 30 | void limits_disable(); 31 | 32 | // Returns limit state as a bit-wise uint8 variable. 33 | uint8_t limits_get_state(); 34 | 35 | // Perform one portion of the homing cycle based on the input settings. 36 | void limits_go_home(uint8_t cycle_mask); 37 | 38 | // Check for soft limit violations 39 | void limits_soft_check(float *target); 40 | 41 | #endif 42 | -------------------------------------------------------------------------------- /grbl/main.c: -------------------------------------------------------------------------------- 1 | /* 2 | main.c - An embedded CNC Controller with rs274/ngc (g-code) support 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #include "grbl.h" 23 | 24 | 25 | // Declare system global variable structure 26 | system_t sys; 27 | int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps. 28 | int32_t sys_probe_position[N_AXIS]; // Last probe position in machine coordinates and steps. 29 | volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR. 30 | volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks. 31 | volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms. 32 | volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides. 33 | volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides. 34 | #ifdef DEBUG 35 | volatile uint8_t sys_rt_exec_debug; 36 | #endif 37 | 38 | 39 | int main(void) 40 | { 41 | // Initialize system upon power-up. 42 | serial_init(); // Setup serial baud rate and interrupts 43 | settings_init(); // Load Grbl settings from EEPROM 44 | stepper_init(); // Configure stepper pins and interrupt timers 45 | system_init(); // Configure pinout pins and pin-change interrupt 46 | 47 | memset(sys_position,0,sizeof(sys_position)); // Clear machine position. 48 | sei(); // Enable interrupts 49 | 50 | // Initialize system state. 51 | #ifdef FORCE_INITIALIZATION_ALARM 52 | // Force Grbl into an ALARM state upon a power-cycle or hard reset. 53 | sys.state = STATE_ALARM; 54 | #else 55 | sys.state = STATE_IDLE; 56 | #endif 57 | 58 | // Check for power-up and set system alarm if homing is enabled to force homing cycle 59 | // by setting Grbl's alarm state. Alarm locks out all g-code commands, including the 60 | // startup scripts, but allows access to settings and internal commands. Only a homing 61 | // cycle '$H' or kill alarm locks '$X' will disable the alarm. 62 | // NOTE: The startup script will run after successful completion of the homing cycle, but 63 | // not after disabling the alarm locks. Prevents motion startup blocks from crashing into 64 | // things uncontrollably. Very bad. 65 | #ifdef HOMING_INIT_LOCK 66 | if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { sys.state = STATE_ALARM; } 67 | #endif 68 | 69 | // Grbl initialization loop upon power-up or a system abort. For the latter, all processes 70 | // will return to this loop to be cleanly re-initialized. 71 | for(;;) { 72 | 73 | // Reset system variables. 74 | uint8_t prior_state = sys.state; 75 | memset(&sys, 0, sizeof(system_t)); // Clear system struct variable. 76 | sys.state = prior_state; 77 | sys.f_override = DEFAULT_FEED_OVERRIDE; // Set to 100% 78 | sys.r_override = DEFAULT_RAPID_OVERRIDE; // Set to 100% 79 | sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE; // Set to 100% 80 | memset(sys_probe_position,0,sizeof(sys_probe_position)); // Clear probe position. 81 | sys_probe_state = 0; 82 | sys_rt_exec_state = 0; 83 | sys_rt_exec_alarm = 0; 84 | sys_rt_exec_motion_override = 0; 85 | sys_rt_exec_accessory_override = 0; 86 | 87 | // Reset Grbl primary systems. 88 | serial_reset_read_buffer(); // Clear serial read buffer 89 | gc_init(); // Set g-code parser to default state 90 | spindle_init(); 91 | coolant_init(); 92 | limits_init(); 93 | probe_init(); 94 | plan_reset(); // Clear block buffer and planner variables 95 | st_reset(); // Clear stepper subsystem variables. 96 | 97 | // Sync cleared gcode and planner positions to current system position. 98 | plan_sync_position(); 99 | gc_sync_position(); 100 | 101 | // Print welcome message. Indicates an initialization has occured at power-up or with a reset. 102 | report_init_message(); 103 | 104 | // Start Grbl main loop. Processes program inputs and executes them. 105 | protocol_main_loop(); 106 | 107 | } 108 | return 0; /* Never reached */ 109 | } 110 | -------------------------------------------------------------------------------- /grbl/motion_control.h: -------------------------------------------------------------------------------- 1 | /* 2 | motion_control.h - high level interface for issuing motion commands 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef motion_control_h 23 | #define motion_control_h 24 | 25 | 26 | // System motion commands must have a line number of zero. 27 | #define HOMING_CYCLE_LINE_NUMBER 0 28 | #define PARKING_MOTION_LINE_NUMBER 0 29 | 30 | #define HOMING_CYCLE_ALL 0 // Must be zero. 31 | #define HOMING_CYCLE_X bit(X_AXIS) 32 | #define HOMING_CYCLE_Y bit(Y_AXIS) 33 | #define HOMING_CYCLE_Z bit(Z_AXIS) 34 | 35 | 36 | // Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second 37 | // unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in 38 | // (1 minute)/feed_rate time. 39 | void mc_line(float *target, plan_line_data_t *pl_data); 40 | 41 | // Execute an arc in offset mode format. position == current xyz, target == target xyz, 42 | // offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is 43 | // the direction of helical travel, radius == circle radius, is_clockwise_arc boolean. Used 44 | // for vector transformation direction. 45 | void mc_arc(float *target, plan_line_data_t *pl_data, float *position, float *offset, float radius, 46 | uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc); 47 | 48 | // Dwell for a specific number of seconds 49 | void mc_dwell(float seconds); 50 | 51 | // Perform homing cycle to locate machine zero. Requires limit switches. 52 | void mc_homing_cycle(uint8_t cycle_mask); 53 | 54 | // Perform tool length probe cycle. Requires probe switch. 55 | uint8_t mc_probe_cycle(float *target, plan_line_data_t *pl_data, uint8_t parser_flags); 56 | 57 | // Handles updating the override control state. 58 | void mc_override_ctrl_update(uint8_t override_state); 59 | 60 | // Plans and executes the single special motion case for parking. Independent of main planner buffer. 61 | void mc_parking_motion(float *parking_target, plan_line_data_t *pl_data); 62 | 63 | // Performs system reset. If in motion state, kills all motion and sets system alarm. 64 | void mc_reset(); 65 | 66 | #endif 67 | -------------------------------------------------------------------------------- /grbl/nuts_bolts.c: -------------------------------------------------------------------------------- 1 | /* 2 | nuts_bolts.c - Shared functions 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #include "grbl.h" 23 | 24 | 25 | #define MAX_INT_DIGITS 8 // Maximum number of digits in int32 (and float) 26 | 27 | 28 | // Extracts a floating point value from a string. The following code is based loosely on 29 | // the avr-libc strtod() function by Michael Stumpf and Dmitry Xmelkov and many freely 30 | // available conversion method examples, but has been highly optimized for Grbl. For known 31 | // CNC applications, the typical decimal value is expected to be in the range of E0 to E-4. 32 | // Scientific notation is officially not supported by g-code, and the 'E' character may 33 | // be a g-code word on some CNC systems. So, 'E' notation will not be recognized. 34 | // NOTE: Thanks to Radu-Eosif Mihailescu for identifying the issues with using strtod(). 35 | uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr) 36 | { 37 | char *ptr = line + *char_counter; 38 | unsigned char c; 39 | 40 | // Grab first character and increment pointer. No spaces assumed in line. 41 | c = *ptr++; 42 | 43 | // Capture initial positive/minus character 44 | bool isnegative = false; 45 | if (c == '-') { 46 | isnegative = true; 47 | c = *ptr++; 48 | } else if (c == '+') { 49 | c = *ptr++; 50 | } 51 | 52 | // Extract number into fast integer. Track decimal in terms of exponent value. 53 | uint32_t intval = 0; 54 | int8_t exp = 0; 55 | uint8_t ndigit = 0; 56 | bool isdecimal = false; 57 | while(1) { 58 | c -= '0'; 59 | if (c <= 9) { 60 | ndigit++; 61 | if (ndigit <= MAX_INT_DIGITS) { 62 | if (isdecimal) { exp--; } 63 | intval = (((intval << 2) + intval) << 1) + c; // intval*10 + c 64 | } else { 65 | if (!(isdecimal)) { exp++; } // Drop overflow digits 66 | } 67 | } else if (c == (('.'-'0') & 0xff) && !(isdecimal)) { 68 | isdecimal = true; 69 | } else { 70 | break; 71 | } 72 | c = *ptr++; 73 | } 74 | 75 | // Return if no digits have been read. 76 | if (!ndigit) { return(false); }; 77 | 78 | // Convert integer into floating point. 79 | float fval; 80 | fval = (float)intval; 81 | 82 | // Apply decimal. Should perform no more than two floating point multiplications for the 83 | // expected range of E0 to E-4. 84 | if (fval != 0) { 85 | while (exp <= -2) { 86 | fval *= 0.01; 87 | exp += 2; 88 | } 89 | if (exp < 0) { 90 | fval *= 0.1; 91 | } else if (exp > 0) { 92 | do { 93 | fval *= 10.0; 94 | } while (--exp > 0); 95 | } 96 | } 97 | 98 | // Assign floating point value with correct sign. 99 | if (isnegative) { 100 | *float_ptr = -fval; 101 | } else { 102 | *float_ptr = fval; 103 | } 104 | 105 | *char_counter = ptr - line - 1; // Set char_counter to next statement 106 | 107 | return(true); 108 | } 109 | 110 | 111 | // Non-blocking delay function used for general operation and suspend features. 112 | void delay_sec(float seconds, uint8_t mode) 113 | { 114 | uint16_t i = ceil(1000/DWELL_TIME_STEP*seconds); 115 | while (i-- > 0) { 116 | if (sys.abort) { return; } 117 | if (mode == DELAY_MODE_DWELL) { 118 | protocol_execute_realtime(); 119 | } else { // DELAY_MODE_SYS_SUSPEND 120 | // Execute rt_system() only to avoid nesting suspend loops. 121 | protocol_exec_rt_system(); 122 | if (sys.suspend & SUSPEND_RESTART_RETRACT) { return; } // Bail, if safety door reopens. 123 | } 124 | _delay_ms(DWELL_TIME_STEP); // Delay DWELL_TIME_STEP increment 125 | } 126 | } 127 | 128 | 129 | // Delays variable defined milliseconds. Compiler compatibility fix for _delay_ms(), 130 | // which only accepts constants in future compiler releases. 131 | void delay_ms(uint16_t ms) 132 | { 133 | while ( ms-- ) { _delay_ms(1); } 134 | } 135 | 136 | 137 | // Delays variable defined microseconds. Compiler compatibility fix for _delay_us(), 138 | // which only accepts constants in future compiler releases. Written to perform more 139 | // efficiently with larger delays, as the counter adds parasitic time in each iteration. 140 | void delay_us(uint32_t us) 141 | { 142 | while (us) { 143 | if (us < 10) { 144 | _delay_us(1); 145 | us--; 146 | } else if (us < 100) { 147 | _delay_us(10); 148 | us -= 10; 149 | } else if (us < 1000) { 150 | _delay_us(100); 151 | us -= 100; 152 | } else { 153 | _delay_ms(1); 154 | us -= 1000; 155 | } 156 | } 157 | } 158 | 159 | 160 | // Simple hypotenuse computation function. 161 | float hypot_f(float x, float y) { return(sqrt(x*x + y*y)); } 162 | 163 | 164 | float convert_delta_vector_to_unit_vector(float *vector) 165 | { 166 | uint8_t idx; 167 | float magnitude = 0.0; 168 | for (idx=0; idx. 20 | */ 21 | 22 | #ifndef nuts_bolts_h 23 | #define nuts_bolts_h 24 | 25 | #define false 0 26 | #define true 1 27 | 28 | #define SOME_LARGE_VALUE 1.0E+38 29 | 30 | // Axis array index values. Must start with 0 and be continuous. 31 | #define N_AXIS 3 // Number of axes 32 | #define X_AXIS 0 // Axis indexing value. 33 | #define Y_AXIS 1 34 | #define Z_AXIS 2 35 | // #define A_AXIS 3 36 | 37 | // CoreXY motor assignments. DO NOT ALTER. 38 | // NOTE: If the A and B motor axis bindings are changed, this effects the CoreXY equations. 39 | #ifdef COREXY 40 | #define A_MOTOR X_AXIS // Must be X_AXIS 41 | #define B_MOTOR Y_AXIS // Must be Y_AXIS 42 | #endif 43 | 44 | // Conversions 45 | #define MM_PER_INCH (25.40) 46 | #define INCH_PER_MM (0.0393701) 47 | #define TICKS_PER_MICROSECOND (F_CPU/1000000) 48 | 49 | #define DELAY_MODE_DWELL 0 50 | #define DELAY_MODE_SYS_SUSPEND 1 51 | 52 | // Useful macros 53 | #define clear_vector(a) memset(a, 0, sizeof(a)) 54 | #define clear_vector_float(a) memset(a, 0.0, sizeof(float)*N_AXIS) 55 | // #define clear_vector_long(a) memset(a, 0.0, sizeof(long)*N_AXIS) 56 | #define max(a,b) (((a) > (b)) ? (a) : (b)) 57 | #define min(a,b) (((a) < (b)) ? (a) : (b)) 58 | #define isequal_position_vector(a,b) !(memcmp(a, b, sizeof(float)*N_AXIS)) 59 | 60 | // Bit field and masking macros 61 | #define bit(n) (1 << n) 62 | #define bit_true(x,mask) (x) |= (mask) 63 | #define bit_false(x,mask) (x) &= ~(mask) 64 | #define bit_istrue(x,mask) ((x & mask) != 0) 65 | #define bit_isfalse(x,mask) ((x & mask) == 0) 66 | 67 | // Read a floating point value from a string. Line points to the input buffer, char_counter 68 | // is the indexer pointing to the current character of the line, while float_ptr is 69 | // a pointer to the result variable. Returns true when it succeeds 70 | uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr); 71 | 72 | // Non-blocking delay function used for general operation and suspend features. 73 | void delay_sec(float seconds, uint8_t mode); 74 | 75 | // Delays variable-defined milliseconds. Compiler compatibility fix for _delay_ms(). 76 | void delay_ms(uint16_t ms); 77 | 78 | // Delays variable-defined microseconds. Compiler compatibility fix for _delay_us(). 79 | void delay_us(uint32_t us); 80 | 81 | // Computes hypotenuse, avoiding avr-gcc's bloated version and the extra error checking. 82 | float hypot_f(float x, float y); 83 | 84 | float convert_delta_vector_to_unit_vector(float *vector); 85 | float limit_value_by_axis_maximum(float *max_value, float *unit_vec); 86 | 87 | #endif 88 | -------------------------------------------------------------------------------- /grbl/planner.h: -------------------------------------------------------------------------------- 1 | /* 2 | planner.h - buffers movement commands and manages the acceleration profile plan 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef planner_h 23 | #define planner_h 24 | 25 | 26 | // The number of linear motions that can be in the plan at any give time 27 | #ifndef BLOCK_BUFFER_SIZE 28 | #ifdef USE_LINE_NUMBERS 29 | #define BLOCK_BUFFER_SIZE 15 30 | #else 31 | #define BLOCK_BUFFER_SIZE 16 32 | #endif 33 | #endif 34 | 35 | // Returned status message from planner. 36 | #define PLAN_OK true 37 | #define PLAN_EMPTY_BLOCK false 38 | 39 | // Define planner data condition flags. Used to denote running conditions of a block. 40 | #define PL_COND_FLAG_RAPID_MOTION bit(0) 41 | #define PL_COND_FLAG_SYSTEM_MOTION bit(1) // Single motion. Circumvents planner state. Used by home/park. 42 | #define PL_COND_FLAG_NO_FEED_OVERRIDE bit(2) // Motion does not honor feed override. 43 | #define PL_COND_FLAG_INVERSE_TIME bit(3) // Interprets feed rate value as inverse time when set. 44 | #define PL_COND_FLAG_SPINDLE_CW bit(4) 45 | #define PL_COND_FLAG_SPINDLE_CCW bit(5) 46 | #define PL_COND_FLAG_COOLANT_FLOOD bit(6) 47 | #define PL_COND_FLAG_COOLANT_MIST bit(7) 48 | #define PL_COND_MOTION_MASK (PL_COND_FLAG_RAPID_MOTION|PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE) 49 | #define PL_COND_SPINDLE_MASK (PL_COND_FLAG_SPINDLE_CW|PL_COND_FLAG_SPINDLE_CCW) 50 | #define PL_COND_ACCESSORY_MASK (PL_COND_FLAG_SPINDLE_CW|PL_COND_FLAG_SPINDLE_CCW|PL_COND_FLAG_COOLANT_FLOOD|PL_COND_FLAG_COOLANT_MIST) 51 | 52 | 53 | // This struct stores a linear movement of a g-code block motion with its critical "nominal" values 54 | // are as specified in the source g-code. 55 | typedef struct { 56 | // Fields used by the bresenham algorithm for tracing the line 57 | // NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values. 58 | uint32_t steps[N_AXIS]; // Step count along each axis 59 | uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block. 60 | uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h) 61 | 62 | // Block condition data to ensure correct execution depending on states and overrides. 63 | uint8_t condition; // Block bitflag variable defining block run conditions. Copied from pl_line_data. 64 | #ifdef USE_LINE_NUMBERS 65 | int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data. 66 | #endif 67 | 68 | // Fields used by the motion planner to manage acceleration. Some of these values may be updated 69 | // by the stepper module during execution of special motion cases for replanning purposes. 70 | float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2 71 | float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and 72 | // neighboring nominal speeds with overrides in (mm/min)^2 73 | float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2). Does not change. 74 | float millimeters; // The remaining distance for this block to be executed in (mm). 75 | // NOTE: This value may be altered by stepper algorithm during execution. 76 | 77 | // Stored rate limiting data used by planner when changes occur. 78 | float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2 79 | float rapid_rate; // Axis-limit adjusted maximum rate for this block direction in (mm/min) 80 | float programmed_rate; // Programmed rate of this block (mm/min). 81 | 82 | #ifdef VARIABLE_SPINDLE 83 | // Stored spindle speed data used by spindle overrides and resuming methods. 84 | float spindle_speed; // Block spindle speed. Copied from pl_line_data. 85 | #endif 86 | } plan_block_t; 87 | 88 | 89 | // Planner data prototype. Must be used when passing new motions to the planner. 90 | typedef struct { 91 | float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion. 92 | float spindle_speed; // Desired spindle speed through line motion. 93 | uint8_t condition; // Bitflag variable to indicate planner conditions. See defines above. 94 | #ifdef USE_LINE_NUMBERS 95 | int32_t line_number; // Desired line number to report when executing. 96 | #endif 97 | } plan_line_data_t; 98 | 99 | 100 | // Initialize and reset the motion plan subsystem 101 | void plan_reset(); // Reset all 102 | void plan_reset_buffer(); // Reset buffer only. 103 | 104 | // Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position 105 | // in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed 106 | // rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes. 107 | uint8_t plan_buffer_line(float *target, plan_line_data_t *pl_data); 108 | 109 | // Called when the current block is no longer needed. Discards the block and makes the memory 110 | // availible for new blocks. 111 | void plan_discard_current_block(); 112 | 113 | // Gets the planner block for the special system motion cases. (Parking/Homing) 114 | plan_block_t *plan_get_system_motion_block(); 115 | 116 | // Gets the current block. Returns NULL if buffer empty 117 | plan_block_t *plan_get_current_block(); 118 | 119 | // Called periodically by step segment buffer. Mostly used internally by planner. 120 | uint8_t plan_next_block_index(uint8_t block_index); 121 | 122 | // Called by step segment buffer when computing executing block velocity profile. 123 | float plan_get_exec_block_exit_speed_sqr(); 124 | 125 | // Called by main program during planner calculations and step segment buffer during initialization. 126 | float plan_compute_profile_nominal_speed(plan_block_t *block); 127 | 128 | // Re-calculates buffered motions profile parameters upon a motion-based override change. 129 | void plan_update_velocity_profile_parameters(); 130 | 131 | // Reset the planner position vector (in steps) 132 | void plan_sync_position(); 133 | 134 | // Reinitialize plan with a partially completed block 135 | void plan_cycle_reinitialize(); 136 | 137 | // Returns the number of available blocks are in the planner buffer. 138 | uint8_t plan_get_block_buffer_available(); 139 | 140 | // Returns the number of active blocks are in the planner buffer. 141 | // NOTE: Deprecated. Not used unless classic status reports are enabled in config.h 142 | uint8_t plan_get_block_buffer_count(); 143 | 144 | // Returns the status of the block ring buffer. True, if buffer is full. 145 | uint8_t plan_check_full_buffer(); 146 | 147 | void plan_get_planner_mpos(float *target); 148 | 149 | 150 | #endif 151 | -------------------------------------------------------------------------------- /grbl/print.c: -------------------------------------------------------------------------------- 1 | /* 2 | print.c - Functions for formatting output strings 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #include "grbl.h" 23 | 24 | 25 | void printString(const char *s) 26 | { 27 | while (*s) 28 | serial_write(*s++); 29 | } 30 | 31 | 32 | // Print a string stored in PGM-memory 33 | void printPgmString(const char *s) 34 | { 35 | char c; 36 | while ((c = pgm_read_byte_near(s++))) 37 | serial_write(c); 38 | } 39 | 40 | 41 | // void printIntegerInBase(unsigned long n, unsigned long base) 42 | // { 43 | // unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars. 44 | // unsigned long i = 0; 45 | // 46 | // if (n == 0) { 47 | // serial_write('0'); 48 | // return; 49 | // } 50 | // 51 | // while (n > 0) { 52 | // buf[i++] = n % base; 53 | // n /= base; 54 | // } 55 | // 56 | // for (; i > 0; i--) 57 | // serial_write(buf[i - 1] < 10 ? 58 | // '0' + buf[i - 1] : 59 | // 'A' + buf[i - 1] - 10); 60 | // } 61 | 62 | 63 | // Prints an uint8 variable in base 10. 64 | void print_uint8_base10(uint8_t n) 65 | { 66 | uint8_t digit_a = 0; 67 | uint8_t digit_b = 0; 68 | if (n >= 100) { // 100-255 69 | digit_a = '0' + n % 10; 70 | n /= 10; 71 | } 72 | if (n >= 10) { // 10-99 73 | digit_b = '0' + n % 10; 74 | n /= 10; 75 | } 76 | serial_write('0' + n); 77 | if (digit_b) { serial_write(digit_b); } 78 | if (digit_a) { serial_write(digit_a); } 79 | } 80 | 81 | 82 | // Prints an uint8 variable in base 2 with desired number of desired digits. 83 | void print_uint8_base2_ndigit(uint8_t n, uint8_t digits) { 84 | unsigned char buf[digits]; 85 | uint8_t i = 0; 86 | 87 | for (; i < digits; i++) { 88 | buf[i] = n % 2 ; 89 | n /= 2; 90 | } 91 | 92 | for (; i > 0; i--) 93 | serial_write('0' + buf[i - 1]); 94 | } 95 | 96 | 97 | void print_uint32_base10(uint32_t n) 98 | { 99 | if (n == 0) { 100 | serial_write('0'); 101 | return; 102 | } 103 | 104 | unsigned char buf[10]; 105 | uint8_t i = 0; 106 | 107 | while (n > 0) { 108 | buf[i++] = n % 10; 109 | n /= 10; 110 | } 111 | 112 | for (; i > 0; i--) 113 | serial_write('0' + buf[i-1]); 114 | } 115 | 116 | 117 | void printInteger(long n) 118 | { 119 | if (n < 0) { 120 | serial_write('-'); 121 | print_uint32_base10(-n); 122 | } else { 123 | print_uint32_base10(n); 124 | } 125 | } 126 | 127 | 128 | // Convert float to string by immediately converting to a long integer, which contains 129 | // more digits than a float. Number of decimal places, which are tracked by a counter, 130 | // may be set by the user. The integer is then efficiently converted to a string. 131 | // NOTE: AVR '%' and '/' integer operations are very efficient. Bitshifting speed-up 132 | // techniques are actually just slightly slower. Found this out the hard way. 133 | void printFloat(float n, uint8_t decimal_places) 134 | { 135 | if (n < 0) { 136 | serial_write('-'); 137 | n = -n; 138 | } 139 | 140 | uint8_t decimals = decimal_places; 141 | while (decimals >= 2) { // Quickly convert values expected to be E0 to E-4. 142 | n *= 100; 143 | decimals -= 2; 144 | } 145 | if (decimals) { n *= 10; } 146 | n += 0.5; // Add rounding factor. Ensures carryover through entire value. 147 | 148 | // Generate digits backwards and store in string. 149 | unsigned char buf[13]; 150 | uint8_t i = 0; 151 | uint32_t a = (long)n; 152 | while(a > 0) { 153 | buf[i++] = (a % 10) + '0'; // Get digit 154 | a /= 10; 155 | } 156 | while (i < decimal_places) { 157 | buf[i++] = '0'; // Fill in zeros to decimal point for (n < 1) 158 | } 159 | if (i == decimal_places) { // Fill in leading zero, if needed. 160 | buf[i++] = '0'; 161 | } 162 | 163 | // Print the generated string. 164 | for (; i > 0; i--) { 165 | if (i == decimal_places) { serial_write('.'); } // Insert decimal point in right place. 166 | serial_write(buf[i-1]); 167 | } 168 | } 169 | 170 | 171 | // Floating value printing handlers for special variables types used in Grbl and are defined 172 | // in the config.h. 173 | // - CoordValue: Handles all position or coordinate values in inches or mm reporting. 174 | // - RateValue: Handles feed rate and current velocity in inches or mm reporting. 175 | void printFloat_CoordValue(float n) { 176 | if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) { 177 | printFloat(n*INCH_PER_MM,N_DECIMAL_COORDVALUE_INCH); 178 | } else { 179 | printFloat(n,N_DECIMAL_COORDVALUE_MM); 180 | } 181 | } 182 | 183 | void printFloat_RateValue(float n) { 184 | if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) { 185 | printFloat(n*INCH_PER_MM,N_DECIMAL_RATEVALUE_INCH); 186 | } else { 187 | printFloat(n,N_DECIMAL_RATEVALUE_MM); 188 | } 189 | } 190 | 191 | // Debug tool to print free memory in bytes at the called point. 192 | // NOTE: Keep commented unless using. Part of this function always gets compiled in. 193 | // void printFreeMemory() 194 | // { 195 | // extern int __heap_start, *__brkval; 196 | // uint16_t free; // Up to 64k values. 197 | // free = (int) &free - (__brkval == 0 ? (int) &__heap_start : (int) __brkval); 198 | // printInteger((int32_t)free); 199 | // printString(" "); 200 | // } 201 | -------------------------------------------------------------------------------- /grbl/print.h: -------------------------------------------------------------------------------- 1 | /* 2 | print.h - Functions for formatting output strings 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef print_h 23 | #define print_h 24 | 25 | 26 | void printString(const char *s); 27 | 28 | void printPgmString(const char *s); 29 | 30 | void printInteger(long n); 31 | 32 | void print_uint32_base10(uint32_t n); 33 | 34 | // Prints an uint8 variable in base 10. 35 | void print_uint8_base10(uint8_t n); 36 | 37 | // Prints an uint8 variable in base 2 with desired number of desired digits. 38 | void print_uint8_base2_ndigit(uint8_t n, uint8_t digits); 39 | 40 | void printFloat(float n, uint8_t decimal_places); 41 | 42 | // Floating value printing handlers for special variables types used in Grbl. 43 | // - CoordValue: Handles all position or coordinate values in inches or mm reporting. 44 | // - RateValue: Handles feed rate and current velocity in inches or mm reporting. 45 | void printFloat_CoordValue(float n); 46 | void printFloat_RateValue(float n); 47 | 48 | // Debug tool to print free memory in bytes at the called point. Not used otherwise. 49 | void printFreeMemory(); 50 | 51 | #endif 52 | -------------------------------------------------------------------------------- /grbl/probe.c: -------------------------------------------------------------------------------- 1 | /* 2 | probe.c - code pertaining to probing methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #include "grbl.h" 22 | 23 | 24 | // Inverts the probe pin state depending on user settings and probing cycle mode. 25 | uint8_t probe_invert_mask; 26 | 27 | 28 | // Probe pin initialization routine. 29 | void probe_init() 30 | { 31 | PROBE_DDR &= ~(PROBE_MASK); // Configure as input pins 32 | #ifdef DISABLE_PROBE_PIN_PULL_UP 33 | PROBE_PORT &= ~(PROBE_MASK); // Normal low operation. Requires external pull-down. 34 | #else 35 | PROBE_PORT |= PROBE_MASK; // Enable internal pull-up resistors. Normal high operation. 36 | #endif 37 | probe_configure_invert_mask(false); // Initialize invert mask. 38 | } 39 | 40 | 41 | // Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to 42 | // appropriately set the pin logic according to setting for normal-high/normal-low operation 43 | // and the probing cycle modes for toward-workpiece/away-from-workpiece. 44 | void probe_configure_invert_mask(uint8_t is_probe_away) 45 | { 46 | probe_invert_mask = 0; // Initialize as zero. 47 | if (bit_isfalse(settings.flags,BITFLAG_INVERT_PROBE_PIN)) { probe_invert_mask ^= PROBE_MASK; } 48 | if (is_probe_away) { probe_invert_mask ^= PROBE_MASK; } 49 | } 50 | 51 | 52 | // Returns the probe pin state. Triggered = true. Called by gcode parser and probe state monitor. 53 | uint8_t probe_get_state() { return((PROBE_PIN & PROBE_MASK) ^ probe_invert_mask); } 54 | 55 | 56 | // Monitors probe pin state and records the system position when detected. Called by the 57 | // stepper ISR per ISR tick. 58 | // NOTE: This function must be extremely efficient as to not bog down the stepper ISR. 59 | void probe_state_monitor() 60 | { 61 | if (probe_get_state()) { 62 | sys_probe_state = PROBE_OFF; 63 | memcpy(sys_probe_position, sys_position, sizeof(sys_position)); 64 | bit_true(sys_rt_exec_state, EXEC_MOTION_CANCEL); 65 | } 66 | } 67 | -------------------------------------------------------------------------------- /grbl/probe.h: -------------------------------------------------------------------------------- 1 | /* 2 | probe.h - code pertaining to probing methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #ifndef probe_h 22 | #define probe_h 23 | 24 | // Values that define the probing state machine. 25 | #define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.) 26 | #define PROBE_ACTIVE 1 // Actively watching the input pin. 27 | 28 | // Probe pin initialization routine. 29 | void probe_init(); 30 | 31 | // Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to 32 | // appropriately set the pin logic according to setting for normal-high/normal-low operation 33 | // and the probing cycle modes for toward-workpiece/away-from-workpiece. 34 | void probe_configure_invert_mask(uint8_t is_probe_away); 35 | 36 | // Returns probe pin state. Triggered = true. Called by gcode parser and probe state monitor. 37 | uint8_t probe_get_state(); 38 | 39 | // Monitors probe pin state and records the system position when detected. Called by the 40 | // stepper ISR per ISR tick. 41 | void probe_state_monitor(); 42 | 43 | #endif 44 | -------------------------------------------------------------------------------- /grbl/protocol.h: -------------------------------------------------------------------------------- 1 | /* 2 | protocol.h - controls Grbl execution protocol and procedures 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef protocol_h 23 | #define protocol_h 24 | 25 | // Line buffer size from the serial input stream to be executed. 26 | // NOTE: Not a problem except for extreme cases, but the line buffer size can be too small 27 | // and g-code blocks can get truncated. Officially, the g-code standards support up to 256 28 | // characters. In future versions, this will be increased, when we know how much extra 29 | // memory space we can invest into here or we re-write the g-code parser not to have this 30 | // buffer. 31 | #ifndef LINE_BUFFER_SIZE 32 | #define LINE_BUFFER_SIZE 80 33 | #endif 34 | 35 | // Starts Grbl main loop. It handles all incoming characters from the serial port and executes 36 | // them as they complete. It is also responsible for finishing the initialization procedures. 37 | void protocol_main_loop(); 38 | 39 | // Checks and executes a realtime command at various stop points in main program 40 | void protocol_execute_realtime(); 41 | void protocol_exec_rt_system(); 42 | 43 | // Executes the auto cycle feature, if enabled. 44 | void protocol_auto_cycle_start(); 45 | 46 | // Block until all buffered steps are executed 47 | void protocol_buffer_synchronize(); 48 | 49 | #endif 50 | -------------------------------------------------------------------------------- /grbl/report.h: -------------------------------------------------------------------------------- 1 | /* 2 | report.h - reporting and messaging methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | #ifndef report_h 21 | #define report_h 22 | 23 | // Define Grbl status codes. Valid values (0-255) 24 | #define STATUS_OK 0 25 | #define STATUS_EXPECTED_COMMAND_LETTER 1 26 | #define STATUS_BAD_NUMBER_FORMAT 2 27 | #define STATUS_INVALID_STATEMENT 3 28 | #define STATUS_NEGATIVE_VALUE 4 29 | #define STATUS_SETTING_DISABLED 5 30 | #define STATUS_SETTING_STEP_PULSE_MIN 6 31 | #define STATUS_SETTING_READ_FAIL 7 32 | #define STATUS_IDLE_ERROR 8 33 | #define STATUS_SYSTEM_GC_LOCK 9 34 | #define STATUS_SOFT_LIMIT_ERROR 10 35 | #define STATUS_OVERFLOW 11 36 | #define STATUS_MAX_STEP_RATE_EXCEEDED 12 37 | #define STATUS_CHECK_DOOR 13 38 | #define STATUS_LINE_LENGTH_EXCEEDED 14 39 | #define STATUS_TRAVEL_EXCEEDED 15 40 | #define STATUS_INVALID_JOG_COMMAND 16 41 | #define STATUS_SETTING_DISABLED_LASER 17 42 | 43 | #define STATUS_GCODE_UNSUPPORTED_COMMAND 20 44 | #define STATUS_GCODE_MODAL_GROUP_VIOLATION 21 45 | #define STATUS_GCODE_UNDEFINED_FEED_RATE 22 46 | #define STATUS_GCODE_COMMAND_VALUE_NOT_INTEGER 23 47 | #define STATUS_GCODE_AXIS_COMMAND_CONFLICT 24 48 | #define STATUS_GCODE_WORD_REPEATED 25 49 | #define STATUS_GCODE_NO_AXIS_WORDS 26 50 | #define STATUS_GCODE_INVALID_LINE_NUMBER 27 51 | #define STATUS_GCODE_VALUE_WORD_MISSING 28 52 | #define STATUS_GCODE_UNSUPPORTED_COORD_SYS 29 53 | #define STATUS_GCODE_G53_INVALID_MOTION_MODE 30 54 | #define STATUS_GCODE_AXIS_WORDS_EXIST 31 55 | #define STATUS_GCODE_NO_AXIS_WORDS_IN_PLANE 32 56 | #define STATUS_GCODE_INVALID_TARGET 33 57 | #define STATUS_GCODE_ARC_RADIUS_ERROR 34 58 | #define STATUS_GCODE_NO_OFFSETS_IN_PLANE 35 59 | #define STATUS_GCODE_UNUSED_WORDS 36 60 | #define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37 61 | #define STATUS_GCODE_MAX_VALUE_EXCEEDED 38 62 | 63 | // Define Grbl alarm codes. Valid values (1-255). 0 is reserved. 64 | #define ALARM_HARD_LIMIT_ERROR EXEC_ALARM_HARD_LIMIT 65 | #define ALARM_SOFT_LIMIT_ERROR EXEC_ALARM_SOFT_LIMIT 66 | #define ALARM_ABORT_CYCLE EXEC_ALARM_ABORT_CYCLE 67 | #define ALARM_PROBE_FAIL_INITIAL EXEC_ALARM_PROBE_FAIL_INITIAL 68 | #define ALARM_PROBE_FAIL_CONTACT EXEC_ALARM_PROBE_FAIL_CONTACT 69 | #define ALARM_HOMING_FAIL_RESET EXEC_ALARM_HOMING_FAIL_RESET 70 | #define ALARM_HOMING_FAIL_DOOR EXEC_ALARM_HOMING_FAIL_DOOR 71 | #define ALARM_HOMING_FAIL_PULLOFF EXEC_ALARM_HOMING_FAIL_PULLOFF 72 | #define ALARM_HOMING_FAIL_APPROACH EXEC_ALARM_HOMING_FAIL_APPROACH 73 | 74 | // Define Grbl feedback message codes. Valid values (0-255). 75 | #define MESSAGE_CRITICAL_EVENT 1 76 | #define MESSAGE_ALARM_LOCK 2 77 | #define MESSAGE_ALARM_UNLOCK 3 78 | #define MESSAGE_ENABLED 4 79 | #define MESSAGE_DISABLED 5 80 | #define MESSAGE_SAFETY_DOOR_AJAR 6 81 | #define MESSAGE_CHECK_LIMITS 7 82 | #define MESSAGE_PROGRAM_END 8 83 | #define MESSAGE_RESTORE_DEFAULTS 9 84 | #define MESSAGE_SPINDLE_RESTORE 10 85 | #define MESSAGE_SLEEP_MODE 11 86 | 87 | // Prints system status messages. 88 | void report_status_message(uint8_t status_code); 89 | 90 | // Prints system alarm messages. 91 | void report_alarm_message(uint8_t alarm_code); 92 | 93 | // Prints miscellaneous feedback messages. 94 | void report_feedback_message(uint8_t message_code); 95 | 96 | // Prints welcome message 97 | void report_init_message(); 98 | 99 | // Prints Grbl help and current global settings 100 | void report_grbl_help(); 101 | 102 | // Prints Grbl global settings 103 | void report_grbl_settings(); 104 | 105 | // Prints an echo of the pre-parsed line received right before execution. 106 | void report_echo_line_received(char *line); 107 | 108 | // Prints realtime status report 109 | void report_realtime_status(); 110 | 111 | // Prints recorded probe position 112 | void report_probe_parameters(); 113 | 114 | // Prints Grbl NGC parameters (coordinate offsets, probe) 115 | void report_ngc_parameters(); 116 | 117 | // Prints current g-code parser mode state 118 | void report_gcode_modes(); 119 | 120 | // Prints startup line when requested and executed. 121 | void report_startup_line(uint8_t n, char *line); 122 | void report_execute_startup_message(char *line, uint8_t status_code); 123 | 124 | // Prints build info and user info 125 | void report_build_info(char *line); 126 | 127 | #ifdef DEBUG 128 | void report_realtime_debug(); 129 | #endif 130 | 131 | #endif 132 | -------------------------------------------------------------------------------- /grbl/serial.c: -------------------------------------------------------------------------------- 1 | /* 2 | serial.c - Low level functions for sending and recieving bytes via the serial port 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #include "grbl.h" 23 | 24 | #define RX_RING_BUFFER (RX_BUFFER_SIZE+1) 25 | #define TX_RING_BUFFER (TX_BUFFER_SIZE+1) 26 | 27 | uint8_t serial_rx_buffer[RX_RING_BUFFER]; 28 | uint8_t serial_rx_buffer_head = 0; 29 | volatile uint8_t serial_rx_buffer_tail = 0; 30 | 31 | uint8_t serial_tx_buffer[TX_RING_BUFFER]; 32 | uint8_t serial_tx_buffer_head = 0; 33 | volatile uint8_t serial_tx_buffer_tail = 0; 34 | 35 | 36 | // Returns the number of bytes available in the RX serial buffer. 37 | uint8_t serial_get_rx_buffer_available() 38 | { 39 | uint8_t rtail = serial_rx_buffer_tail; // Copy to limit multiple calls to volatile 40 | if (serial_rx_buffer_head >= rtail) { return(RX_BUFFER_SIZE - (serial_rx_buffer_head-rtail)); } 41 | return((rtail-serial_rx_buffer_head-1)); 42 | } 43 | 44 | 45 | // Returns the number of bytes used in the RX serial buffer. 46 | // NOTE: Deprecated. Not used unless classic status reports are enabled in config.h. 47 | uint8_t serial_get_rx_buffer_count() 48 | { 49 | uint8_t rtail = serial_rx_buffer_tail; // Copy to limit multiple calls to volatile 50 | if (serial_rx_buffer_head >= rtail) { return(serial_rx_buffer_head-rtail); } 51 | return (RX_BUFFER_SIZE - (rtail-serial_rx_buffer_head)); 52 | } 53 | 54 | 55 | // Returns the number of bytes used in the TX serial buffer. 56 | // NOTE: Not used except for debugging and ensuring no TX bottlenecks. 57 | uint8_t serial_get_tx_buffer_count() 58 | { 59 | uint8_t ttail = serial_tx_buffer_tail; // Copy to limit multiple calls to volatile 60 | if (serial_tx_buffer_head >= ttail) { return(serial_tx_buffer_head-ttail); } 61 | return (TX_RING_BUFFER - (ttail-serial_tx_buffer_head)); 62 | } 63 | 64 | 65 | void serial_init() 66 | { 67 | // Set baud rate 68 | #if BAUD_RATE < 57600 69 | uint16_t UBRR0_value = ((F_CPU / (8L * BAUD_RATE)) - 1)/2 ; 70 | UCSR0A &= ~(1 << U2X0); // baud doubler off - Only needed on Uno XXX 71 | #else 72 | uint16_t UBRR0_value = ((F_CPU / (4L * BAUD_RATE)) - 1)/2; 73 | UCSR0A |= (1 << U2X0); // baud doubler on for high baud rates, i.e. 115200 74 | #endif 75 | UBRR0H = UBRR0_value >> 8; 76 | UBRR0L = UBRR0_value; 77 | 78 | // enable rx, tx, and interrupt on complete reception of a byte 79 | UCSR0B |= (1< 0x7F) { // Real-time control characters are extended ACSII only. 157 | switch(data) { 158 | case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true 159 | case CMD_JOG_CANCEL: 160 | if (sys.state & STATE_JOG) { // Block all other states from invoking motion cancel. 161 | system_set_exec_state_flag(EXEC_MOTION_CANCEL); 162 | } 163 | break; 164 | #ifdef DEBUG 165 | case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug,EXEC_DEBUG_REPORT); SREG = sreg;} break; 166 | #endif 167 | case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break; 168 | case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break; 169 | case CMD_FEED_OVR_COARSE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_MINUS); break; 170 | case CMD_FEED_OVR_FINE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_PLUS); break; 171 | case CMD_FEED_OVR_FINE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_MINUS); break; 172 | case CMD_RAPID_OVR_RESET: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_RESET); break; 173 | case CMD_RAPID_OVR_MEDIUM: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_MEDIUM); break; 174 | case CMD_RAPID_OVR_LOW: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_LOW); break; 175 | case CMD_SPINDLE_OVR_RESET: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_RESET); break; 176 | case CMD_SPINDLE_OVR_COARSE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_PLUS); break; 177 | case CMD_SPINDLE_OVR_COARSE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_MINUS); break; 178 | case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break; 179 | case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break; 180 | case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break; 181 | case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break; 182 | #ifdef ENABLE_M7 183 | case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break; 184 | #endif 185 | } 186 | // Throw away any unfound extended-ASCII character by not passing it to the serial buffer. 187 | } else { // Write character to buffer 188 | next_head = serial_rx_buffer_head + 1; 189 | if (next_head == RX_RING_BUFFER) { next_head = 0; } 190 | 191 | // Write data to buffer unless it is full. 192 | if (next_head != serial_rx_buffer_tail) { 193 | serial_rx_buffer[serial_rx_buffer_head] = data; 194 | serial_rx_buffer_head = next_head; 195 | } 196 | } 197 | } 198 | } 199 | 200 | 201 | void serial_reset_read_buffer() 202 | { 203 | serial_rx_buffer_tail = serial_rx_buffer_head; 204 | } 205 | -------------------------------------------------------------------------------- /grbl/serial.h: -------------------------------------------------------------------------------- 1 | /* 2 | serial.c - Low level functions for sending and recieving bytes via the serial port 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef serial_h 23 | #define serial_h 24 | 25 | 26 | #ifndef RX_BUFFER_SIZE 27 | #define RX_BUFFER_SIZE 128 28 | #endif 29 | #ifndef TX_BUFFER_SIZE 30 | #ifdef USE_LINE_NUMBERS 31 | #define TX_BUFFER_SIZE 112 32 | #else 33 | #define TX_BUFFER_SIZE 104 34 | #endif 35 | #endif 36 | 37 | #define SERIAL_NO_DATA 0xff 38 | 39 | 40 | void serial_init(); 41 | 42 | // Writes one byte to the TX serial buffer. Called by main program. 43 | void serial_write(uint8_t data); 44 | 45 | // Fetches the first byte in the serial read buffer. Called by main program. 46 | uint8_t serial_read(); 47 | 48 | // Reset and empty data in read buffer. Used by e-stop and reset. 49 | void serial_reset_read_buffer(); 50 | 51 | // Returns the number of bytes available in the RX serial buffer. 52 | uint8_t serial_get_rx_buffer_available(); 53 | 54 | // Returns the number of bytes used in the RX serial buffer. 55 | // NOTE: Deprecated. Not used unless classic status reports are enabled in config.h. 56 | uint8_t serial_get_rx_buffer_count(); 57 | 58 | // Returns the number of bytes used in the TX serial buffer. 59 | // NOTE: Not used except for debugging and ensuring no TX bottlenecks. 60 | uint8_t serial_get_tx_buffer_count(); 61 | 62 | #endif 63 | -------------------------------------------------------------------------------- /grbl/settings.c: -------------------------------------------------------------------------------- 1 | /* 2 | settings.c - eeprom configuration handling 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #include "grbl.h" 23 | 24 | settings_t settings; 25 | 26 | const __flash settings_t defaults = {\ 27 | .pulse_microseconds = DEFAULT_STEP_PULSE_MICROSECONDS, 28 | .stepper_idle_lock_time = DEFAULT_STEPPER_IDLE_LOCK_TIME, 29 | .step_invert_mask = DEFAULT_STEPPING_INVERT_MASK, 30 | .dir_invert_mask = DEFAULT_DIRECTION_INVERT_MASK, 31 | .status_report_mask = DEFAULT_STATUS_REPORT_MASK, 32 | .junction_deviation = DEFAULT_JUNCTION_DEVIATION, 33 | .arc_tolerance = DEFAULT_ARC_TOLERANCE, 34 | .rpm_max = DEFAULT_SPINDLE_RPM_MAX, 35 | .rpm_min = DEFAULT_SPINDLE_RPM_MIN, 36 | .homing_dir_mask = DEFAULT_HOMING_DIR_MASK, 37 | .homing_feed_rate = DEFAULT_HOMING_FEED_RATE, 38 | .homing_seek_rate = DEFAULT_HOMING_SEEK_RATE, 39 | .homing_debounce_delay = DEFAULT_HOMING_DEBOUNCE_DELAY, 40 | .homing_pulloff = DEFAULT_HOMING_PULLOFF, 41 | .flags = (DEFAULT_REPORT_INCHES << BIT_REPORT_INCHES) | \ 42 | (DEFAULT_LASER_MODE << BIT_LASER_MODE) | \ 43 | (DEFAULT_INVERT_ST_ENABLE << BIT_INVERT_ST_ENABLE) | \ 44 | (DEFAULT_HARD_LIMIT_ENABLE << BIT_HARD_LIMIT_ENABLE) | \ 45 | (DEFAULT_HOMING_ENABLE << BIT_HOMING_ENABLE) | \ 46 | (DEFAULT_SOFT_LIMIT_ENABLE << BIT_SOFT_LIMIT_ENABLE) | \ 47 | (DEFAULT_INVERT_LIMIT_PINS << BIT_INVERT_LIMIT_PINS) | \ 48 | (DEFAULT_INVERT_PROBE_PIN << BIT_INVERT_PROBE_PIN), 49 | .steps_per_mm[X_AXIS] = DEFAULT_X_STEPS_PER_MM, 50 | .steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM, 51 | .steps_per_mm[Z_AXIS] = DEFAULT_Z_STEPS_PER_MM, 52 | .max_rate[X_AXIS] = DEFAULT_X_MAX_RATE, 53 | .max_rate[Y_AXIS] = DEFAULT_Y_MAX_RATE, 54 | .max_rate[Z_AXIS] = DEFAULT_Z_MAX_RATE, 55 | .acceleration[X_AXIS] = DEFAULT_X_ACCELERATION, 56 | .acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION, 57 | .acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION, 58 | .max_travel[X_AXIS] = (-DEFAULT_X_MAX_TRAVEL), 59 | .max_travel[Y_AXIS] = (-DEFAULT_Y_MAX_TRAVEL), 60 | .max_travel[Z_AXIS] = (-DEFAULT_Z_MAX_TRAVEL)}; 61 | 62 | 63 | // Method to store startup lines into EEPROM 64 | void settings_store_startup_line(uint8_t n, char *line) 65 | { 66 | #ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE 67 | protocol_buffer_synchronize(); // A startup line may contain a motion and be executing. 68 | #endif 69 | uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK; 70 | memcpy_to_eeprom_with_checksum(addr,(char*)line, LINE_BUFFER_SIZE); 71 | } 72 | 73 | 74 | // Method to store build info into EEPROM 75 | // NOTE: This function can only be called in IDLE state. 76 | void settings_store_build_info(char *line) 77 | { 78 | // Build info can only be stored when state is IDLE. 79 | memcpy_to_eeprom_with_checksum(EEPROM_ADDR_BUILD_INFO,(char*)line, LINE_BUFFER_SIZE); 80 | } 81 | 82 | 83 | // Method to store coord data parameters into EEPROM 84 | void settings_write_coord_data(uint8_t coord_select, float *coord_data) 85 | { 86 | #ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE 87 | protocol_buffer_synchronize(); 88 | #endif 89 | uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS; 90 | memcpy_to_eeprom_with_checksum(addr,(char*)coord_data, sizeof(float)*N_AXIS); 91 | } 92 | 93 | 94 | // Method to store Grbl global settings struct and version number into EEPROM 95 | // NOTE: This function can only be called in IDLE state. 96 | void write_global_settings() 97 | { 98 | eeprom_put_char(0, SETTINGS_VERSION); 99 | memcpy_to_eeprom_with_checksum(EEPROM_ADDR_GLOBAL, (char*)&settings, sizeof(settings_t)); 100 | } 101 | 102 | 103 | // Method to restore EEPROM-saved Grbl global settings back to defaults. 104 | void settings_restore(uint8_t restore_flag) { 105 | if (restore_flag & SETTINGS_RESTORE_DEFAULTS) { 106 | settings = defaults; 107 | write_global_settings(); 108 | } 109 | 110 | if (restore_flag & SETTINGS_RESTORE_PARAMETERS) { 111 | uint8_t idx; 112 | float coord_data[N_AXIS]; 113 | memset(&coord_data, 0, sizeof(coord_data)); 114 | for (idx=0; idx <= SETTING_INDEX_NCOORD; idx++) { settings_write_coord_data(idx, coord_data); } 115 | } 116 | 117 | if (restore_flag & SETTINGS_RESTORE_STARTUP_LINES) { 118 | #if N_STARTUP_LINE > 0 119 | eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK, 0); 120 | eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+1, 0); // Checksum 121 | #endif 122 | #if N_STARTUP_LINE > 1 123 | eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+1), 0); 124 | eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+2), 0); // Checksum 125 | #endif 126 | } 127 | 128 | if (restore_flag & SETTINGS_RESTORE_BUILD_INFO) { 129 | eeprom_put_char(EEPROM_ADDR_BUILD_INFO , 0); 130 | eeprom_put_char(EEPROM_ADDR_BUILD_INFO+1 , 0); // Checksum 131 | } 132 | } 133 | 134 | 135 | // Reads startup line from EEPROM. Updated pointed line string data. 136 | uint8_t settings_read_startup_line(uint8_t n, char *line) 137 | { 138 | uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK; 139 | if (!(memcpy_from_eeprom_with_checksum((char*)line, addr, LINE_BUFFER_SIZE))) { 140 | // Reset line with default value 141 | line[0] = 0; // Empty line 142 | settings_store_startup_line(n, line); 143 | return(false); 144 | } 145 | return(true); 146 | } 147 | 148 | 149 | // Reads startup line from EEPROM. Updated pointed line string data. 150 | uint8_t settings_read_build_info(char *line) 151 | { 152 | if (!(memcpy_from_eeprom_with_checksum((char*)line, EEPROM_ADDR_BUILD_INFO, LINE_BUFFER_SIZE))) { 153 | // Reset line with default value 154 | line[0] = 0; // Empty line 155 | settings_store_build_info(line); 156 | return(false); 157 | } 158 | return(true); 159 | } 160 | 161 | 162 | // Read selected coordinate data from EEPROM. Updates pointed coord_data value. 163 | uint8_t settings_read_coord_data(uint8_t coord_select, float *coord_data) 164 | { 165 | uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS; 166 | if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float)*N_AXIS))) { 167 | // Reset with default zero vector 168 | clear_vector_float(coord_data); 169 | settings_write_coord_data(coord_select,coord_data); 170 | return(false); 171 | } 172 | return(true); 173 | } 174 | 175 | 176 | // Reads Grbl global settings struct from EEPROM. 177 | uint8_t read_global_settings() { 178 | // Check version-byte of eeprom 179 | uint8_t version = eeprom_get_char(0); 180 | if (version == SETTINGS_VERSION) { 181 | // Read settings-record and check checksum 182 | if (!(memcpy_from_eeprom_with_checksum((char*)&settings, EEPROM_ADDR_GLOBAL, sizeof(settings_t)))) { 183 | return(false); 184 | } 185 | } else { 186 | return(false); 187 | } 188 | return(true); 189 | } 190 | 191 | 192 | // A helper method to set settings from command line 193 | uint8_t settings_store_global_setting(uint8_t parameter, float value) { 194 | if (value < 0.0) { return(STATUS_NEGATIVE_VALUE); } 195 | if (parameter >= AXIS_SETTINGS_START_VAL) { 196 | // Store axis configuration. Axis numbering sequence set by AXIS_SETTING defines. 197 | // NOTE: Ensure the setting index corresponds to the report.c settings printout. 198 | parameter -= AXIS_SETTINGS_START_VAL; 199 | uint8_t set_idx = 0; 200 | while (set_idx < AXIS_N_SETTINGS) { 201 | if (parameter < N_AXIS) { 202 | // Valid axis setting found. 203 | switch (set_idx) { 204 | case 0: 205 | #ifdef MAX_STEP_RATE_HZ 206 | if (value*settings.max_rate[parameter] > (MAX_STEP_RATE_HZ*60.0)) { return(STATUS_MAX_STEP_RATE_EXCEEDED); } 207 | #endif 208 | settings.steps_per_mm[parameter] = value; 209 | break; 210 | case 1: 211 | #ifdef MAX_STEP_RATE_HZ 212 | if (value*settings.steps_per_mm[parameter] > (MAX_STEP_RATE_HZ*60.0)) { return(STATUS_MAX_STEP_RATE_EXCEEDED); } 213 | #endif 214 | settings.max_rate[parameter] = value; 215 | break; 216 | case 2: settings.acceleration[parameter] = value*60*60; break; // Convert to mm/min^2 for grbl internal use. 217 | case 3: settings.max_travel[parameter] = -value; break; // Store as negative for grbl internal use. 218 | } 219 | break; // Exit while-loop after setting has been configured and proceed to the EEPROM write call. 220 | } else { 221 | set_idx++; 222 | // If axis index greater than N_AXIS or setting index greater than number of axis settings, error out. 223 | if ((parameter < AXIS_SETTINGS_INCREMENT) || (set_idx == AXIS_N_SETTINGS)) { return(STATUS_INVALID_STATEMENT); } 224 | parameter -= AXIS_SETTINGS_INCREMENT; 225 | } 226 | } 227 | } else { 228 | // Store non-axis Grbl settings 229 | uint8_t int_value = trunc(value); 230 | switch(parameter) { 231 | case 0: 232 | if (int_value < 3) { return(STATUS_SETTING_STEP_PULSE_MIN); } 233 | settings.pulse_microseconds = int_value; break; 234 | case 1: settings.stepper_idle_lock_time = int_value; break; 235 | case 2: 236 | settings.step_invert_mask = int_value; 237 | st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks. 238 | break; 239 | case 3: 240 | settings.dir_invert_mask = int_value; 241 | st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks. 242 | break; 243 | case 4: // Reset to ensure change. Immediate re-init may cause problems. 244 | if (int_value) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; } 245 | else { settings.flags &= ~BITFLAG_INVERT_ST_ENABLE; } 246 | break; 247 | case 5: // Reset to ensure change. Immediate re-init may cause problems. 248 | if (int_value) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; } 249 | else { settings.flags &= ~BITFLAG_INVERT_LIMIT_PINS; } 250 | break; 251 | case 6: // Reset to ensure change. Immediate re-init may cause problems. 252 | if (int_value) { settings.flags |= BITFLAG_INVERT_PROBE_PIN; } 253 | else { settings.flags &= ~BITFLAG_INVERT_PROBE_PIN; } 254 | probe_configure_invert_mask(false); 255 | break; 256 | case 10: settings.status_report_mask = int_value; break; 257 | case 11: settings.junction_deviation = value; break; 258 | case 12: settings.arc_tolerance = value; break; 259 | case 13: 260 | if (int_value) { settings.flags |= BITFLAG_REPORT_INCHES; } 261 | else { settings.flags &= ~BITFLAG_REPORT_INCHES; } 262 | system_flag_wco_change(); // Make sure WCO is immediately updated. 263 | break; 264 | case 20: 265 | if (int_value) { 266 | if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) { return(STATUS_SOFT_LIMIT_ERROR); } 267 | settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; 268 | } else { settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; } 269 | break; 270 | case 21: 271 | if (int_value) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; } 272 | else { settings.flags &= ~BITFLAG_HARD_LIMIT_ENABLE; } 273 | limits_init(); // Re-init to immediately change. NOTE: Nice to have but could be problematic later. 274 | break; 275 | case 22: 276 | if (int_value) { settings.flags |= BITFLAG_HOMING_ENABLE; } 277 | else { 278 | settings.flags &= ~BITFLAG_HOMING_ENABLE; 279 | settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; // Force disable soft-limits. 280 | } 281 | break; 282 | case 23: settings.homing_dir_mask = int_value; break; 283 | case 24: settings.homing_feed_rate = value; break; 284 | case 25: settings.homing_seek_rate = value; break; 285 | case 26: settings.homing_debounce_delay = int_value; break; 286 | case 27: settings.homing_pulloff = value; break; 287 | case 30: settings.rpm_max = value; spindle_init(); break; // Re-initialize spindle rpm calibration 288 | case 31: settings.rpm_min = value; spindle_init(); break; // Re-initialize spindle rpm calibration 289 | case 32: 290 | #ifdef VARIABLE_SPINDLE 291 | if (int_value) { settings.flags |= BITFLAG_LASER_MODE; } 292 | else { settings.flags &= ~BITFLAG_LASER_MODE; } 293 | #else 294 | return(STATUS_SETTING_DISABLED_LASER); 295 | #endif 296 | break; 297 | default: 298 | return(STATUS_INVALID_STATEMENT); 299 | } 300 | } 301 | write_global_settings(); 302 | return(STATUS_OK); 303 | } 304 | 305 | 306 | // Initialize the config subsystem 307 | void settings_init() { 308 | if(!read_global_settings()) { 309 | report_status_message(STATUS_SETTING_READ_FAIL); 310 | settings_restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data. 311 | report_grbl_settings(); 312 | } 313 | } 314 | 315 | 316 | // Returns step pin mask according to Grbl internal axis indexing. 317 | uint8_t get_step_pin_mask(uint8_t axis_idx) 318 | { 319 | if ( axis_idx == X_AXIS ) { return((1<. 20 | */ 21 | 22 | #ifndef settings_h 23 | #define settings_h 24 | 25 | #include "grbl.h" 26 | 27 | 28 | // Version of the EEPROM data. Will be used to migrate existing data from older versions of Grbl 29 | // when firmware is upgraded. Always stored in byte 0 of eeprom 30 | #define SETTINGS_VERSION 10 // NOTE: Check settings_reset() when moving to next version. 31 | 32 | // Define bit flag masks for the boolean settings in settings.flag. 33 | #define BIT_REPORT_INCHES 0 34 | #define BIT_LASER_MODE 1 35 | #define BIT_INVERT_ST_ENABLE 2 36 | #define BIT_HARD_LIMIT_ENABLE 3 37 | #define BIT_HOMING_ENABLE 4 38 | #define BIT_SOFT_LIMIT_ENABLE 5 39 | #define BIT_INVERT_LIMIT_PINS 6 40 | #define BIT_INVERT_PROBE_PIN 7 41 | 42 | #define BITFLAG_REPORT_INCHES bit(BIT_REPORT_INCHES) 43 | #define BITFLAG_LASER_MODE bit(BIT_LASER_MODE) 44 | #define BITFLAG_INVERT_ST_ENABLE bit(BIT_INVERT_ST_ENABLE) 45 | #define BITFLAG_HARD_LIMIT_ENABLE bit(BIT_HARD_LIMIT_ENABLE) 46 | #define BITFLAG_HOMING_ENABLE bit(BIT_HOMING_ENABLE) 47 | #define BITFLAG_SOFT_LIMIT_ENABLE bit(BIT_SOFT_LIMIT_ENABLE) 48 | #define BITFLAG_INVERT_LIMIT_PINS bit(BIT_INVERT_LIMIT_PINS) 49 | #define BITFLAG_INVERT_PROBE_PIN bit(BIT_INVERT_PROBE_PIN) 50 | 51 | // Define status reporting boolean enable bit flags in settings.status_report_mask 52 | #define BITFLAG_RT_STATUS_POSITION_TYPE bit(0) 53 | #define BITFLAG_RT_STATUS_BUFFER_STATE bit(1) 54 | 55 | // Define settings restore bitflags. 56 | #define SETTINGS_RESTORE_DEFAULTS bit(0) 57 | #define SETTINGS_RESTORE_PARAMETERS bit(1) 58 | #define SETTINGS_RESTORE_STARTUP_LINES bit(2) 59 | #define SETTINGS_RESTORE_BUILD_INFO bit(3) 60 | #ifndef SETTINGS_RESTORE_ALL 61 | #define SETTINGS_RESTORE_ALL 0xFF // All bitflags 62 | #endif 63 | 64 | // Define EEPROM memory address location values for Grbl settings and parameters 65 | // NOTE: The Atmega328p has 1KB EEPROM. The upper half is reserved for parameters and 66 | // the startup script. The lower half contains the global settings and space for future 67 | // developments. 68 | #define EEPROM_ADDR_GLOBAL 1U 69 | #define EEPROM_ADDR_PARAMETERS 512U 70 | #define EEPROM_ADDR_STARTUP_BLOCK 768U 71 | #define EEPROM_ADDR_BUILD_INFO 942U 72 | 73 | // Define EEPROM address indexing for coordinate parameters 74 | #define N_COORDINATE_SYSTEM 6 // Number of supported work coordinate systems (from index 1) 75 | #define SETTING_INDEX_NCOORD N_COORDINATE_SYSTEM+1 // Total number of system stored (from index 0) 76 | // NOTE: Work coordinate indices are (0=G54, 1=G55, ... , 6=G59) 77 | #define SETTING_INDEX_G28 N_COORDINATE_SYSTEM // Home position 1 78 | #define SETTING_INDEX_G30 N_COORDINATE_SYSTEM+1 // Home position 2 79 | // #define SETTING_INDEX_G92 N_COORDINATE_SYSTEM+2 // Coordinate offset (G92.2,G92.3 not supported) 80 | 81 | // Define Grbl axis settings numbering scheme. Starts at START_VAL, every INCREMENT, over N_SETTINGS. 82 | #define AXIS_N_SETTINGS 4 83 | #define AXIS_SETTINGS_START_VAL 100 // NOTE: Reserving settings values >= 100 for axis settings. Up to 255. 84 | #define AXIS_SETTINGS_INCREMENT 10 // Must be greater than the number of axis settings 85 | 86 | // Global persistent settings (Stored from byte EEPROM_ADDR_GLOBAL onwards) 87 | typedef struct { 88 | // Axis settings 89 | float steps_per_mm[N_AXIS]; 90 | float max_rate[N_AXIS]; 91 | float acceleration[N_AXIS]; 92 | float max_travel[N_AXIS]; 93 | 94 | // Remaining Grbl settings 95 | uint8_t pulse_microseconds; 96 | uint8_t step_invert_mask; 97 | uint8_t dir_invert_mask; 98 | uint8_t stepper_idle_lock_time; // If max value 255, steppers do not disable. 99 | uint8_t status_report_mask; // Mask to indicate desired report data. 100 | float junction_deviation; 101 | float arc_tolerance; 102 | 103 | float rpm_max; 104 | float rpm_min; 105 | 106 | uint8_t flags; // Contains default boolean settings 107 | 108 | uint8_t homing_dir_mask; 109 | float homing_feed_rate; 110 | float homing_seek_rate; 111 | uint16_t homing_debounce_delay; 112 | float homing_pulloff; 113 | } settings_t; 114 | extern settings_t settings; 115 | 116 | // Initialize the configuration subsystem (load settings from EEPROM) 117 | void settings_init(); 118 | 119 | // Helper function to clear and restore EEPROM defaults 120 | void settings_restore(uint8_t restore_flag); 121 | 122 | // A helper method to set new settings from command line 123 | uint8_t settings_store_global_setting(uint8_t parameter, float value); 124 | 125 | // Stores the protocol line variable as a startup line in EEPROM 126 | void settings_store_startup_line(uint8_t n, char *line); 127 | 128 | // Reads an EEPROM startup line to the protocol line variable 129 | uint8_t settings_read_startup_line(uint8_t n, char *line); 130 | 131 | // Stores build info user-defined string 132 | void settings_store_build_info(char *line); 133 | 134 | // Reads build info user-defined string 135 | uint8_t settings_read_build_info(char *line); 136 | 137 | // Writes selected coordinate data to EEPROM 138 | void settings_write_coord_data(uint8_t coord_select, float *coord_data); 139 | 140 | // Reads selected coordinate data from EEPROM 141 | uint8_t settings_read_coord_data(uint8_t coord_select, float *coord_data); 142 | 143 | // Returns the step pin mask according to Grbl's internal axis numbering 144 | uint8_t get_step_pin_mask(uint8_t i); 145 | 146 | // Returns the direction pin mask according to Grbl's internal axis numbering 147 | uint8_t get_direction_pin_mask(uint8_t i); 148 | 149 | // Returns the limit pin mask according to Grbl's internal axis numbering 150 | uint8_t get_limit_pin_mask(uint8_t i); 151 | 152 | 153 | #endif 154 | -------------------------------------------------------------------------------- /grbl/spindle_control.c: -------------------------------------------------------------------------------- 1 | /* 2 | spindle_control.c - spindle control methods 3 | Part of Grbl 4 | 5 | Copyright (c) 2012-2017 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #include "grbl.h" 23 | 24 | 25 | #ifdef VARIABLE_SPINDLE 26 | static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions. 27 | #endif 28 | 29 | 30 | void spindle_init() 31 | { 32 | #ifdef VARIABLE_SPINDLE 33 | // Configure variable spindle PWM and enable pin, if requried. On the Uno, PWM and enable are 34 | // combined unless configured otherwise. 35 | SPINDLE_PWM_DDR |= (1<= settings.rpm_max) || (rpm >= RPM_MAX)) { 155 | rpm = RPM_MAX; 156 | pwm_value = SPINDLE_PWM_MAX_VALUE; 157 | } else if (rpm <= RPM_MIN) { 158 | if (rpm == 0.0) { // S0 disables spindle 159 | pwm_value = SPINDLE_PWM_OFF_VALUE; 160 | } else { 161 | rpm = RPM_MIN; 162 | pwm_value = SPINDLE_PWM_MIN_VALUE; 163 | } 164 | } else { 165 | // Compute intermediate PWM value with linear spindle speed model via piecewise linear fit model. 166 | #if (N_PIECES > 3) 167 | if (rpm > RPM_POINT34) { 168 | pwm_value = floor(RPM_LINE_A4*rpm - RPM_LINE_B4); 169 | } else 170 | #endif 171 | #if (N_PIECES > 2) 172 | if (rpm > RPM_POINT23) { 173 | pwm_value = floor(RPM_LINE_A3*rpm - RPM_LINE_B3); 174 | } else 175 | #endif 176 | #if (N_PIECES > 1) 177 | if (rpm > RPM_POINT12) { 178 | pwm_value = floor(RPM_LINE_A2*rpm - RPM_LINE_B2); 179 | } else 180 | #endif 181 | { 182 | pwm_value = floor(RPM_LINE_A1*rpm - RPM_LINE_B1); 183 | } 184 | } 185 | sys.spindle_speed = rpm; 186 | return(pwm_value); 187 | } 188 | 189 | #else 190 | 191 | // Called by spindle_set_state() and step segment generator. Keep routine small and efficient. 192 | uint8_t spindle_compute_pwm_value(float rpm) // 328p PWM register is 8-bit. 193 | { 194 | uint8_t pwm_value; 195 | rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value. 196 | // Calculate PWM register value based on rpm max/min settings and programmed rpm. 197 | if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) { 198 | // No PWM range possible. Set simple on/off spindle control pin state. 199 | sys.spindle_speed = settings.rpm_max; 200 | pwm_value = SPINDLE_PWM_MAX_VALUE; 201 | } else if (rpm <= settings.rpm_min) { 202 | if (rpm == 0.0) { // S0 disables spindle 203 | sys.spindle_speed = 0.0; 204 | pwm_value = SPINDLE_PWM_OFF_VALUE; 205 | } else { // Set minimum PWM output 206 | sys.spindle_speed = settings.rpm_min; 207 | pwm_value = SPINDLE_PWM_MIN_VALUE; 208 | } 209 | } else { 210 | // Compute intermediate PWM value with linear spindle speed model. 211 | // NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight. 212 | sys.spindle_speed = rpm; 213 | pwm_value = floor((rpm-settings.rpm_min)*pwm_gradient) + SPINDLE_PWM_MIN_VALUE; 214 | } 215 | return(pwm_value); 216 | } 217 | 218 | #endif 219 | #endif 220 | 221 | 222 | // Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled. 223 | // Called by g-code parser spindle_sync(), parking retract and restore, g-code program end, 224 | // sleep, and spindle stop override. 225 | #ifdef VARIABLE_SPINDLE 226 | void spindle_set_state(uint8_t state, float rpm) 227 | #else 228 | void _spindle_set_state(uint8_t state) 229 | #endif 230 | { 231 | if (sys.abort) { return; } // Block during abort. 232 | 233 | if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm. 234 | 235 | #ifdef VARIABLE_SPINDLE 236 | sys.spindle_speed = 0.0; 237 | #endif 238 | spindle_stop(); 239 | 240 | } else { 241 | 242 | #if !defined(USE_SPINDLE_DIR_AS_ENABLE_PIN) && !defined(ENABLE_DUAL_AXIS) 243 | if (state == SPINDLE_ENABLE_CW) { 244 | SPINDLE_DIRECTION_PORT &= ~(1<. 20 | */ 21 | 22 | #ifndef spindle_control_h 23 | #define spindle_control_h 24 | 25 | #define SPINDLE_NO_SYNC false 26 | #define SPINDLE_FORCE_SYNC true 27 | 28 | #define SPINDLE_STATE_DISABLE 0 // Must be zero. 29 | #define SPINDLE_STATE_CW bit(0) 30 | #define SPINDLE_STATE_CCW bit(1) 31 | 32 | 33 | // Initializes spindle pins and hardware PWM, if enabled. 34 | void spindle_init(); 35 | 36 | // Returns current spindle output state. Overrides may alter it from programmed states. 37 | uint8_t spindle_get_state(); 38 | 39 | // Called by g-code parser when setting spindle state and requires a buffer sync. 40 | // Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled. 41 | // Called by spindle_sync() after sync and parking motion/spindle stop override during restore. 42 | #ifdef VARIABLE_SPINDLE 43 | 44 | // Called by g-code parser when setting spindle state and requires a buffer sync. 45 | void spindle_sync(uint8_t state, float rpm); 46 | 47 | // Sets spindle running state with direction, enable, and spindle PWM. 48 | void spindle_set_state(uint8_t state, float rpm); 49 | 50 | // Sets spindle PWM quickly for stepper ISR. Also called by spindle_set_state(). 51 | // NOTE: 328p PWM register is 8-bit. 52 | void spindle_set_speed(uint8_t pwm_value); 53 | 54 | // Computes 328p-specific PWM register value for the given RPM for quick updating. 55 | uint8_t spindle_compute_pwm_value(float rpm); 56 | 57 | #else 58 | 59 | // Called by g-code parser when setting spindle state and requires a buffer sync. 60 | #define spindle_sync(state, rpm) _spindle_sync(state) 61 | void _spindle_sync(uint8_t state); 62 | 63 | // Sets spindle running state with direction and enable. 64 | #define spindle_set_state(state, rpm) _spindle_set_state(state) 65 | void _spindle_set_state(uint8_t state); 66 | 67 | #endif 68 | 69 | // Stop and start spindle routines. Called by all spindle routines and stepper ISR. 70 | void spindle_stop(); 71 | 72 | 73 | #endif 74 | -------------------------------------------------------------------------------- /grbl/stepper.h: -------------------------------------------------------------------------------- 1 | /* 2 | stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors 3 | Part of Grbl 4 | 5 | Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC 6 | Copyright (c) 2009-2011 Simen Svale Skogsrud 7 | 8 | Grbl is free software: you can redistribute it and/or modify 9 | it under the terms of the GNU General Public License as published by 10 | the Free Software Foundation, either version 3 of the License, or 11 | (at your option) any later version. 12 | 13 | Grbl is distributed in the hope that it will be useful, 14 | but WITHOUT ANY WARRANTY; without even the implied warranty of 15 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 16 | GNU General Public License for more details. 17 | 18 | You should have received a copy of the GNU General Public License 19 | along with Grbl. If not, see . 20 | */ 21 | 22 | #ifndef stepper_h 23 | #define stepper_h 24 | 25 | #ifndef SEGMENT_BUFFER_SIZE 26 | #define SEGMENT_BUFFER_SIZE 6 27 | #endif 28 | 29 | // Initialize and setup the stepper motor subsystem 30 | void stepper_init(); 31 | 32 | // Enable steppers, but cycle does not start unless called by motion control or realtime command. 33 | void st_wake_up(); 34 | 35 | // Immediately disables steppers 36 | void st_go_idle(); 37 | 38 | // Generate the step and direction port invert masks. 39 | void st_generate_step_dir_invert_masks(); 40 | 41 | // Reset the stepper subsystem variables 42 | void st_reset(); 43 | 44 | // Changes the run state of the step segment buffer to execute the special parking motion. 45 | void st_parking_setup_buffer(); 46 | 47 | // Restores the step segment buffer to the normal run state after a parking motion. 48 | void st_parking_restore_buffer(); 49 | 50 | // Reloads step segment buffer. Called continuously by realtime execution system. 51 | void st_prep_buffer(); 52 | 53 | // Called by planner_recalculate() when the executing block is updated by the new plan. 54 | void st_update_plan_block_parameters(); 55 | 56 | // Called by realtime status reporting if realtime rate reporting is enabled in config.h. 57 | float st_get_realtime_rate(); 58 | 59 | #endif 60 | -------------------------------------------------------------------------------- /grbl/system.h: -------------------------------------------------------------------------------- 1 | /* 2 | system.h - Header for system level commands and real-time processes 3 | Part of Grbl 4 | 5 | Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC 6 | 7 | Grbl is free software: you can redistribute it and/or modify 8 | it under the terms of the GNU General Public License as published by 9 | the Free Software Foundation, either version 3 of the License, or 10 | (at your option) any later version. 11 | 12 | Grbl is distributed in the hope that it will be useful, 13 | but WITHOUT ANY WARRANTY; without even the implied warranty of 14 | MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 15 | GNU General Public License for more details. 16 | 17 | You should have received a copy of the GNU General Public License 18 | along with Grbl. If not, see . 19 | */ 20 | 21 | #ifndef system_h 22 | #define system_h 23 | 24 | #include "grbl.h" 25 | 26 | // Define system executor bit map. Used internally by realtime protocol as realtime command flags, 27 | // which notifies the main program to execute the specified realtime command asynchronously. 28 | // NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default 29 | // flags are always false, so the realtime protocol only needs to check for a non-zero value to 30 | // know when there is a realtime command to execute. 31 | #define EXEC_STATUS_REPORT bit(0) // bitmask 00000001 32 | #define EXEC_CYCLE_START bit(1) // bitmask 00000010 33 | #define EXEC_CYCLE_STOP bit(2) // bitmask 00000100 34 | #define EXEC_FEED_HOLD bit(3) // bitmask 00001000 35 | #define EXEC_RESET bit(4) // bitmask 00010000 36 | #define EXEC_SAFETY_DOOR bit(5) // bitmask 00100000 37 | #define EXEC_MOTION_CANCEL bit(6) // bitmask 01000000 38 | #define EXEC_SLEEP bit(7) // bitmask 10000000 39 | 40 | // Alarm executor codes. Valid values (1-255). Zero is reserved. 41 | #define EXEC_ALARM_HARD_LIMIT 1 42 | #define EXEC_ALARM_SOFT_LIMIT 2 43 | #define EXEC_ALARM_ABORT_CYCLE 3 44 | #define EXEC_ALARM_PROBE_FAIL_INITIAL 4 45 | #define EXEC_ALARM_PROBE_FAIL_CONTACT 5 46 | #define EXEC_ALARM_HOMING_FAIL_RESET 6 47 | #define EXEC_ALARM_HOMING_FAIL_DOOR 7 48 | #define EXEC_ALARM_HOMING_FAIL_PULLOFF 8 49 | #define EXEC_ALARM_HOMING_FAIL_APPROACH 9 50 | #define EXEC_ALARM_HOMING_FAIL_DUAL_APPROACH 10 51 | 52 | // Override bit maps. Realtime bitflags to control feed, rapid, spindle, and coolant overrides. 53 | // Spindle/coolant and feed/rapids are separated into two controlling flag variables. 54 | #define EXEC_FEED_OVR_RESET bit(0) 55 | #define EXEC_FEED_OVR_COARSE_PLUS bit(1) 56 | #define EXEC_FEED_OVR_COARSE_MINUS bit(2) 57 | #define EXEC_FEED_OVR_FINE_PLUS bit(3) 58 | #define EXEC_FEED_OVR_FINE_MINUS bit(4) 59 | #define EXEC_RAPID_OVR_RESET bit(5) 60 | #define EXEC_RAPID_OVR_MEDIUM bit(6) 61 | #define EXEC_RAPID_OVR_LOW bit(7) 62 | // #define EXEC_RAPID_OVR_EXTRA_LOW bit(*) // *NOT SUPPORTED* 63 | 64 | #define EXEC_SPINDLE_OVR_RESET bit(0) 65 | #define EXEC_SPINDLE_OVR_COARSE_PLUS bit(1) 66 | #define EXEC_SPINDLE_OVR_COARSE_MINUS bit(2) 67 | #define EXEC_SPINDLE_OVR_FINE_PLUS bit(3) 68 | #define EXEC_SPINDLE_OVR_FINE_MINUS bit(4) 69 | #define EXEC_SPINDLE_OVR_STOP bit(5) 70 | #define EXEC_COOLANT_FLOOD_OVR_TOGGLE bit(6) 71 | #define EXEC_COOLANT_MIST_OVR_TOGGLE bit(7) 72 | 73 | // Define system state bit map. The state variable primarily tracks the individual functions 74 | // of Grbl to manage each without overlapping. It is also used as a messaging flag for 75 | // critical events. 76 | #define STATE_IDLE 0 // Must be zero. No flags. 77 | #define STATE_ALARM bit(0) // In alarm state. Locks out all g-code processes. Allows settings access. 78 | #define STATE_CHECK_MODE bit(1) // G-code check mode. Locks out planner and motion only. 79 | #define STATE_HOMING bit(2) // Performing homing cycle 80 | #define STATE_CYCLE bit(3) // Cycle is running or motions are being executed. 81 | #define STATE_HOLD bit(4) // Active feed hold 82 | #define STATE_JOG bit(5) // Jogging mode. 83 | #define STATE_SAFETY_DOOR bit(6) // Safety door is ajar. Feed holds and de-energizes system. 84 | #define STATE_SLEEP bit(7) // Sleep state. 85 | 86 | // Define system suspend flags. Used in various ways to manage suspend states and procedures. 87 | #define SUSPEND_DISABLE 0 // Must be zero. 88 | #define SUSPEND_HOLD_COMPLETE bit(0) // Indicates initial feed hold is complete. 89 | #define SUSPEND_RESTART_RETRACT bit(1) // Flag to indicate a retract from a restore parking motion. 90 | #define SUSPEND_RETRACT_COMPLETE bit(2) // (Safety door only) Indicates retraction and de-energizing is complete. 91 | #define SUSPEND_INITIATE_RESTORE bit(3) // (Safety door only) Flag to initiate resume procedures from a cycle start. 92 | #define SUSPEND_RESTORE_COMPLETE bit(4) // (Safety door only) Indicates ready to resume normal operation. 93 | #define SUSPEND_SAFETY_DOOR_AJAR bit(5) // Tracks safety door state for resuming. 94 | #define SUSPEND_MOTION_CANCEL bit(6) // Indicates a canceled resume motion. Currently used by probing routine. 95 | #define SUSPEND_JOG_CANCEL bit(7) // Indicates a jog cancel in process and to reset buffers when complete. 96 | 97 | // Define step segment generator state flags. 98 | #define STEP_CONTROL_NORMAL_OP 0 // Must be zero. 99 | #define STEP_CONTROL_END_MOTION bit(0) 100 | #define STEP_CONTROL_EXECUTE_HOLD bit(1) 101 | #define STEP_CONTROL_EXECUTE_SYS_MOTION bit(2) 102 | #define STEP_CONTROL_UPDATE_SPINDLE_PWM bit(3) 103 | 104 | // Define control pin index for Grbl internal use. Pin maps may change, but these values don't. 105 | #ifdef ENABLE_SAFETY_DOOR_INPUT_PIN 106 | #define N_CONTROL_PIN 4 107 | #define CONTROL_PIN_INDEX_SAFETY_DOOR bit(0) 108 | #define CONTROL_PIN_INDEX_RESET bit(1) 109 | #define CONTROL_PIN_INDEX_FEED_HOLD bit(2) 110 | #define CONTROL_PIN_INDEX_CYCLE_START bit(3) 111 | #else 112 | #define N_CONTROL_PIN 3 113 | #define CONTROL_PIN_INDEX_RESET bit(0) 114 | #define CONTROL_PIN_INDEX_FEED_HOLD bit(1) 115 | #define CONTROL_PIN_INDEX_CYCLE_START bit(2) 116 | #endif 117 | 118 | // Define spindle stop override control states. 119 | #define SPINDLE_STOP_OVR_DISABLED 0 // Must be zero. 120 | #define SPINDLE_STOP_OVR_ENABLED bit(0) 121 | #define SPINDLE_STOP_OVR_INITIATE bit(1) 122 | #define SPINDLE_STOP_OVR_RESTORE bit(2) 123 | #define SPINDLE_STOP_OVR_RESTORE_CYCLE bit(3) 124 | 125 | 126 | // Define global system variables 127 | typedef struct { 128 | uint8_t state; // Tracks the current system state of Grbl. 129 | uint8_t abort; // System abort flag. Forces exit back to main loop for reset. 130 | uint8_t suspend; // System suspend bitflag variable that manages holds, cancels, and safety door. 131 | uint8_t soft_limit; // Tracks soft limit errors for the state machine. (boolean) 132 | uint8_t step_control; // Governs the step segment generator depending on system state. 133 | uint8_t probe_succeeded; // Tracks if last probing cycle was successful. 134 | uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR. 135 | #ifdef ENABLE_DUAL_AXIS 136 | uint8_t homing_axis_lock_dual; 137 | #endif 138 | uint8_t f_override; // Feed rate override value in percent 139 | uint8_t r_override; // Rapids override value in percent 140 | uint8_t spindle_speed_ovr; // Spindle speed value in percent 141 | uint8_t spindle_stop_ovr; // Tracks spindle stop override states 142 | uint8_t report_ovr_counter; // Tracks when to add override data to status reports. 143 | uint8_t report_wco_counter; // Tracks when to add work coordinate offset data to status reports. 144 | #ifdef ENABLE_PARKING_OVERRIDE_CONTROL 145 | uint8_t override_ctrl; // Tracks override control states. 146 | #endif 147 | #ifdef VARIABLE_SPINDLE 148 | float spindle_speed; 149 | #endif 150 | } system_t; 151 | extern system_t sys; 152 | 153 | // NOTE: These position variables may need to be declared as volatiles, if problems arise. 154 | extern int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps. 155 | extern int32_t sys_probe_position[N_AXIS]; // Last probe position in machine coordinates and steps. 156 | 157 | extern volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR. 158 | extern volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks. 159 | extern volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms. 160 | extern volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides. 161 | extern volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides. 162 | 163 | #ifdef DEBUG 164 | #define EXEC_DEBUG_REPORT bit(0) 165 | extern volatile uint8_t sys_rt_exec_debug; 166 | #endif 167 | 168 | // Initialize the serial protocol 169 | void system_init(); 170 | 171 | // Returns bitfield of control pin states, organized by CONTROL_PIN_INDEX. (1=triggered, 0=not triggered). 172 | uint8_t system_control_get_state(); 173 | 174 | // Returns if safety door is open or closed, based on pin state. 175 | uint8_t system_check_safety_door_ajar(); 176 | 177 | // Executes an internal system command, defined as a string starting with a '$' 178 | uint8_t system_execute_line(char *line); 179 | 180 | // Execute the startup script lines stored in EEPROM upon initialization 181 | void system_execute_startup(char *line); 182 | 183 | 184 | void system_flag_wco_change(); 185 | 186 | // Returns machine position of axis 'idx'. Must be sent a 'step' array. 187 | float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx); 188 | 189 | // Updates a machine 'position' array based on the 'step' array sent. 190 | void system_convert_array_steps_to_mpos(float *position, int32_t *steps); 191 | 192 | // CoreXY calculation only. Returns x or y-axis "steps" based on CoreXY motor steps. 193 | #ifdef COREXY 194 | int32_t system_convert_corexy_to_x_axis_steps(int32_t *steps); 195 | int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps); 196 | #endif 197 | 198 | // Checks and reports if target array exceeds machine travel limits. 199 | uint8_t system_check_travel_limits(float *target); 200 | 201 | // Special handlers for setting and clearing Grbl's real-time execution flags. 202 | void system_set_exec_state_flag(uint8_t mask); 203 | void system_clear_exec_state_flag(uint8_t mask); 204 | void system_set_exec_alarm(uint8_t code); 205 | void system_clear_exec_alarm(); 206 | void system_set_exec_motion_override_flag(uint8_t mask); 207 | void system_set_exec_accessory_override_flag(uint8_t mask); 208 | void system_clear_exec_motion_overrides(); 209 | void system_clear_exec_accessory_overrides(); 210 | 211 | 212 | #endif 213 | --------------------------------------------------------------------------------