Merge branch 'dev' into edge
This commit is contained in:
commit
62d16af285
20
COPYING
20
COPYING
@ -4,7 +4,7 @@ COPYRIGHT NOTICE FOR GRBL:
|
|||||||
|
|
||||||
Grbl - Embedded CNC g-code interpreter and motion-controller
|
Grbl - Embedded CNC g-code interpreter and motion-controller
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
Copyright (c) 2011 Jens Geisler
|
Copyright (c) 2011 Jens Geisler
|
||||||
|
|
||||||
@ -28,27 +28,27 @@ COPYRIGHT NOTICE(S) FOR WORK CONTAINED IN THIS SOFTWARE:
|
|||||||
|
|
||||||
Copyright (c) 2008, Atmel Corporation All rights reserved.
|
Copyright (c) 2008, Atmel Corporation All rights reserved.
|
||||||
|
|
||||||
Redistribution and use in source and binary forms, with or without
|
Redistribution and use in source and binary forms, with or without
|
||||||
modification, are permitted provided that the following conditions are met:
|
modification, are permitted provided that the following conditions are met:
|
||||||
|
|
||||||
1. Redistributions of source code must retain the above copyright notice,
|
1. Redistributions of source code must retain the above copyright notice,
|
||||||
this list of conditions and the following disclaimer.
|
this list of conditions and the following disclaimer.
|
||||||
|
|
||||||
2. Redistributions in binary form must reproduce the above copyright notice,
|
2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
this list of conditions and the following disclaimer in the documentation
|
this list of conditions and the following disclaimer in the documentation
|
||||||
and/or other materials provided with the distribution.
|
and/or other materials provided with the distribution.
|
||||||
|
|
||||||
3. The name of ATMEL may not be used to endorse or promote products derived
|
3. The name of ATMEL may not be used to endorse or promote products derived
|
||||||
from this software without specific prior written permission.
|
from this software without specific prior written permission.
|
||||||
|
|
||||||
THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED
|
||||||
WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
|
||||||
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE EXPRESSLY AND
|
MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE EXPRESSLY AND
|
||||||
SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT,
|
SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR ANY DIRECT,
|
||||||
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||||
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
|
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
|
||||||
DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
|
DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
|
||||||
OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
|
||||||
NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
|
||||||
EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
|
||||||
|
12
Makefile
12
Makefile
@ -1,7 +1,7 @@
|
|||||||
# Part of Grbl
|
# Part of Grbl
|
||||||
#
|
#
|
||||||
# Copyright (c) 2009-2011 Simen Svale Skogsrud
|
# Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
# Copyright (c) 2012-2015 Sungeun K. Jeon
|
# Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
#
|
#
|
||||||
# Grbl is free software: you can redistribute it and/or modify
|
# Grbl is free software: you can redistribute it and/or modify
|
||||||
# it under the terms of the GNU General Public License as published by
|
# it under the terms of the GNU General Public License as published by
|
||||||
@ -32,7 +32,7 @@ DEVICE ?= atmega328p
|
|||||||
CLOCK = 16000000
|
CLOCK = 16000000
|
||||||
PROGRAMMER ?= -c avrisp2 -P usb
|
PROGRAMMER ?= -c avrisp2 -P usb
|
||||||
SOURCE = main.c motion_control.c gcode.c spindle_control.c coolant_control.c serial.c \
|
SOURCE = main.c motion_control.c gcode.c spindle_control.c coolant_control.c serial.c \
|
||||||
protocol.c stepper.c eeprom.c settings.c planner.c nuts_bolts.c limits.c \
|
protocol.c stepper.c eeprom.c settings.c planner.c nuts_bolts.c limits.c jog.c\
|
||||||
print.c probe.c report.c system.c
|
print.c probe.c report.c system.c
|
||||||
BUILDDIR = build
|
BUILDDIR = build
|
||||||
SOURCEDIR = grbl
|
SOURCEDIR = grbl
|
||||||
@ -42,7 +42,13 @@ FUSES = -U hfuse:w:0xd2:m -U lfuse:w:0xff:m
|
|||||||
# Tune the lines below only if you know what you are doing:
|
# Tune the lines below only if you know what you are doing:
|
||||||
|
|
||||||
AVRDUDE = avrdude $(PROGRAMMER) -p $(DEVICE) -B 10 -F
|
AVRDUDE = avrdude $(PROGRAMMER) -p $(DEVICE) -B 10 -F
|
||||||
COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections -fdata-sections
|
|
||||||
|
# Compile flags for avr-gcc v4.8.1. Does not produce -flto warnings.
|
||||||
|
COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections
|
||||||
|
|
||||||
|
# Compile flags for avr-gcc v4.9.2 compatible with the IDE. Or if you don't care about the warnings.
|
||||||
|
# COMPILE = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections -flto
|
||||||
|
|
||||||
|
|
||||||
OBJECTS = $(addprefix $(BUILDDIR)/,$(notdir $(SOURCE:.c=.o)))
|
OBJECTS = $(addprefix $(BUILDDIR)/,$(notdir $(SOURCE:.c=.o)))
|
||||||
|
|
||||||
|
43
README.md
43
README.md
@ -3,25 +3,25 @@
|
|||||||
|
|
||||||
***
|
***
|
||||||
|
|
||||||
_**This is the development branch for Grbl v1.0's upcoming release. In general, the new features here are beta, so use with caution. If you'd like to help, please report any bugs or oddities that you find! Thanks!**_
|
_**This is the development branch for Grbl v1.1's upcoming release. Please keep in mind, the new features here are beta, so use with caution. If you'd like to help, please report any bugs or oddities that you find! Thanks!**_
|
||||||
|
|
||||||
***
|
***
|
||||||
|
|
||||||
Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. It will run on a vanilla Arduino (Duemillanove/Uno) as long as it sports an Atmega 328.
|
Grbl is a no-compromise, high performance, low cost alternative to parallel-port-based motion control for CNC milling. This version of Grbl runs on an Arduino Uno.
|
||||||
|
|
||||||
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.
|
The controller is written in highly optimized C utilizing every clever feature of the AVR-chips to achieve precise timing and asynchronous operation. It is able to maintain up to 30kHz of stable, jitter free control pulses.
|
||||||
|
|
||||||
It accepts standards-compliant g-code and has been tested with the output of several CAM tools with no problems. Arcs, circles and helical motion are fully supported, as well as, all other primary g-code commands. Macro functions, variables, and most canned cycles are not supported, but we think GUIs can do a much better job at translating them into straight g-code anyhow.
|
It accepts standards-compliant g-code and has been tested with the output of several CAM tools with no problems. Arcs, circles and helical motion are fully supported, as well as, all other primary g-code commands. Macro functions, variables, and most canned cycles are not supported, but we think GUIs can do a much better job at translating them into straight g-code anyhow.
|
||||||
|
|
||||||
Grbl includes full acceleration management with look ahead. That means the controller will look up to 18 motions into the future and plan its velocities ahead to deliver smooth acceleration and jerk-free cornering.
|
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.
|
||||||
|
|
||||||
* [Licensing](https://github.com/grbl/grbl/wiki/Licensing): Grbl is free software, released under the GPLv3 license.
|
* [Licensing](https://github.com/gnea/grbl/wiki/Licensing): Grbl is free software, released under the GPLv3 license.
|
||||||
|
|
||||||
* For more information and help, check out our **[Wiki pages!](https://github.com/grbl/grbl/wiki)** If you find that the information is out-dated, please to help us keep it updated by editing it or notifying our community! Thanks!
|
* 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!
|
||||||
|
|
||||||
* Lead Developer [_2011 - Current_]: Sungeun(Sonny) K. Jeon, Ph.D. (USA) aka @chamnit
|
* Lead Developer: Sungeun "Sonny" Jeon, Ph.D. (USA) aka @chamnit
|
||||||
|
|
||||||
* Lead Developer [_2009 - 2011_]: Simen Svale Skogsrud (Norway). aka The Originator/Creator/Pioneer/Father of Grbl.
|
* Built on the wonderful Grbl v0.6 (2011) firmware written by Simen Svale Skogsrud (Norway).
|
||||||
|
|
||||||
***
|
***
|
||||||
|
|
||||||
@ -31,26 +31,41 @@ Grbl includes full acceleration management with look ahead. That means the contr
|
|||||||
|
|
||||||
***
|
***
|
||||||
|
|
||||||
##Update Summary for v1.0c
|
##Update Summary for v1.1
|
||||||
- **IMPORTANT:** Your EEPROM will be wiped and restored with new settings. This is due to the addition of two new spindle speed '$' settings.
|
- **IMPORTANT:** Your EEPROM will be wiped and restored with new settings. This is due to the addition of two new spindle speed '$' settings.
|
||||||
|
|
||||||
- Altered limit pin status reports from `Lim:000` to `Pin:000|0|0000`, where the `|` delimiters separate the new probe state and control pin states. Each new field may be disabled by the `$10` Grbl setting. NOTE: Commenting `REPORT_ALL_PIN_STATES` in config.h reverts to old `Lim:` reports, if needed.
|
- **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.
|
||||||
|
|
||||||
- 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. See config.h for details.
|
- **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.
|
||||||
|
|
||||||
|
- **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.
|
||||||
|
|
||||||
|
- **Sleep Mode** : Grbl may now be put to "sleep" via a `$SLP` command. This will disable everything, including the stepper drivers. Nice to have when you are leaving your machine unattended and want to power down everything automatically. Only a reset exits the sleep state.
|
||||||
|
|
||||||
|
- **Significant Interface Improvements**: Just this one time and done simultaneously with adding override data and controls, Grbl has tweaked the communication interface to make it easier for developers to write and maintain their GUIs. _NOTE: GUIs need to specifically update their code to be compatible with v1.1 and later._
|
||||||
|
|
||||||
|
- **New Status Reports**: To account for the additional override data, status reports have been tweaked to cram more data into it, while still being smaller than before. Documentation is included, outlining how it has been changed.
|
||||||
|
- **Improved Error/Alarm Feedback** : All Grbl error and alarm messages have been changed to providing a code. Each code is associated with a specific problem, so users will know exactly what is wrong without having to guess. Documentation and an easy to parse CSV is included in the repo.
|
||||||
|
- **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.
|
||||||
|
- **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.
|
||||||
|
|
||||||
|
- New OEM specific features, such as safety door parking, single configuration file build option, EEPROM restrictions and restoring controls, and storing product data information.
|
||||||
|
|
||||||
|
- 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.
|
||||||
|
|
||||||
- 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.
|
- 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.
|
||||||
|
|
||||||
- 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.
|
- 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.
|
||||||
|
|
||||||
- **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.
|
- Lots of minor bug fixes and refactoring to make the code more efficient and flexible.
|
||||||
|
|
||||||
- A few bug fixes and lots of refactoring to make the code more efficient and flexible.
|
- **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.
|
||||||
|
|
||||||
|
|
||||||
-
|
-
|
||||||
|
|
||||||
```
|
```
|
||||||
List of Supported G-Codes in Grbl v0.9 Master:
|
List of Supported G-Codes in Grbl v1.1:
|
||||||
- Non-Modal Commands: G4, G10L2, G10L20, G28, G30, G28.1, G30.1, G53, G92, G92.1
|
- Non-Modal Commands: G4, G10L2, G10L20, G28, G30, G28.1, G30.1, G53, G92, G92.1
|
||||||
- Motion Modes: G0, G1, G2, G3, G38.2, G38.3, G38.4, G38.5, G80
|
- Motion Modes: G0, G1, G2, G3, G38.2, G38.3, G38.4, G38.5, G80
|
||||||
- Feed Rate Modes: G93, G94
|
- Feed Rate Modes: G93, G94
|
||||||
|
10
doc/csv/alarm_codes_en_US.csv
Normal file
10
doc/csv/alarm_codes_en_US.csv
Normal file
@ -0,0 +1,10 @@
|
|||||||
|
(KEY: Alarm Code in v1.1+, Alarm Message in v1.0-, Alarm Description)
|
||||||
|
1,Hard limit,Hard limit has been triggered. Machine position is likely lost due to sudden halt. Re-homing is highly recommended.
|
||||||
|
2,Soft limit,Soft limit alarm. G-code motion target exceeds machine travel. Machine position retained. Alarm may be safely unlocked.
|
||||||
|
3,Abort during cycle,Reset while in motion. Machine position is likely lost due to sudden halt. Re-homing is highly recommended.
|
||||||
|
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.
|
||||||
|
5,Probe fail,Probe fail. Probe did not contact the workpiece within the programmed travel for G38.2 and G38.4.
|
||||||
|
6,Homing fail,Homing fail. The active homing cycle was reset.
|
||||||
|
7,Homing fail,Homing fail. Safety door was opened during homing cycle.
|
||||||
|
8,Homing fail,Homing fail. Pull off travel failed to clear limit switch. Try increasing pull-off setting or check wiring.
|
||||||
|
9,Homing fail,Homing fail. Could not find limit switch within search distances. Try increasing max travel, decreasing pull-off distance, or check wiring.
|
|
35
doc/csv/error_codes_en_US.csv
Normal file
35
doc/csv/error_codes_en_US.csv
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
(KEY: Error Code in v1.1+ ,Error Message in v1.0-, Error Description)
|
||||||
|
1,Expected command letter,G-code words consist of a letter and a value. Letter was not found.
|
||||||
|
2,Bad number format,Missing the expected G-code word value or numeric value format is not valid.
|
||||||
|
3,Invalid statement,Grbl '$' system command was not recognized or supported.
|
||||||
|
4,Value < 0,Negative value received for an expected positive value.
|
||||||
|
5,Setting disabled,Homing cycle failure. Homing is not enabled via settings.
|
||||||
|
6,Value < 3 usec,Minimum step pulse time must be greater than 3usec.
|
||||||
|
7,EEPROM read fail. Using defaults,An EEPROM read failed. Auto-restoring affected EEPROM to default values.
|
||||||
|
8,Not idle,Grbl '$' command cannot be used unless Grbl is IDLE. Ensures smooth operation during a job.
|
||||||
|
9,G-code lock,G-code commands are locked out during alarm or jog state.
|
||||||
|
10,Homing not enabled,Soft limits cannot be enabled without homing also enabled.
|
||||||
|
11,Line overflow,Max characters per line exceeded. Received command line was not executed.
|
||||||
|
12,Step rate > 30kHz,Grbl '$' setting value cause the step rate to exceed the maximum supported.
|
||||||
|
13,Check Door,Safety door detected as opened and door state initiated.
|
||||||
|
14,Line length exceeded,Build info or startup line exceeded EEPROM line length limit. Line not stored.
|
||||||
|
15,Travel exceeded,Jog target exceeds machine travel. Jog command has been ignored.
|
||||||
|
16,Invalid jog command,Jog command has no '=' or contains prohibited g-code.
|
||||||
|
20,Unsupported command,Unsupported or invalid g-code command found in block.
|
||||||
|
21,Modal group violation,More than one g-code command from same modal group found in block.
|
||||||
|
22,Undefined feed rate,Feed rate has not yet been set or is undefined.
|
||||||
|
23,Invalid gcode ID:23,G-code command in block requires an integer value.
|
||||||
|
24,Invalid gcode ID:24,More than one g-code command that requires axis words found in block.
|
||||||
|
25,Invalid gcode ID:25,Repeated g-code word found in block.
|
||||||
|
26,Invalid gcode ID:26,No axis words found in block for g-code command or current modal state which requires them.
|
||||||
|
27,Invalid gcode ID:27,Line number value is invalid.
|
||||||
|
28,Invalid gcode ID:28,G-code command is missing a required value word.
|
||||||
|
29,Invalid gcode ID:29,G59.x work coordinate systems are not supported.
|
||||||
|
30,Invalid gcode ID:30,G53 only allowed with G0 and G1 motion modes.
|
||||||
|
31,Invalid gcode ID:31,Axis words found in block when no command or current modal state uses them.
|
||||||
|
32,Invalid gcode ID:32,G2 and G3 arcs require at least one in-plane axis word.
|
||||||
|
33,Invalid gcode ID:33,Motion command target is invalid.
|
||||||
|
34,Invalid gcode ID:34,Arc radius value is invalid.
|
||||||
|
35,Invalid gcode ID:35,G2 and G3 arcs require at least one in-plane offset word.
|
||||||
|
36,Invalid gcode ID:36,Unused value words found in block.
|
||||||
|
37,Invalid gcode ID:37,G43.1 dynamic tool length offset is not assigned to configured tool length axis.
|
|
35
doc/csv/setting_codes_en_US.csv
Normal file
35
doc/csv/setting_codes_en_US.csv
Normal file
@ -0,0 +1,35 @@
|
|||||||
|
(KEY: $-Code, Setting, Units, Setting Description)
|
||||||
|
0,Step pulse time,microseconds,Sets time length per step. Minimum 3usec.
|
||||||
|
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.
|
||||||
|
2,Step pulse invert,mask,Inverts the step signal. Set axis bit to invert (00000ZYX).
|
||||||
|
3,Step direction invert,mask,Inverts the direction signal. Set axis bit to invert (00000ZYX).
|
||||||
|
4,Invert step enable pin,boolean,Inverts the stepper driver enable pin signal.
|
||||||
|
5,Invert limit pins,boolean,Inverts the all of the limit input pins.
|
||||||
|
6,Invert probe pin,boolean,Inverts the probe input pin signal.
|
||||||
|
10,Status report options,mask,Alters data included in status reports.
|
||||||
|
11,Junction deviation,millimeters,Sets how fast Grbl travels through consecutive motions. Lower value slows it down.
|
||||||
|
12,Arc tolerance,millimeters,Sets the G2 and G3 arc tracing accuracy based on radial error. Beware: A very small value may effect performance.
|
||||||
|
13,Report in inches,boolean,Enables inch units when returning any position and rate value that is not a settings value.
|
||||||
|
20,Soft limits enable,boolean,Enables soft limits checks within machine travel and sets alarm when exceeded. Requires homing.
|
||||||
|
21,Hard limits enable,boolean,Enables hard limits. Immediately halts motion and throws an alarm when switch is triggered.
|
||||||
|
22,Homing cycle enable,boolean,Enables homing cycle. Requires limit switches on all axes.
|
||||||
|
23,Homing direction invert,mask,Homing searches for a switch in the positive direction. Set axis bit (00000ZYX) to search in negative direction.
|
||||||
|
24,Homing locate feed rate,mm/min,Feed rate to slowly engage limit switch to determine its location accurately.
|
||||||
|
25,Homing search seek rate,mm/min,Seek rate to quickly find the limit switch before the slower locating phase.
|
||||||
|
26,Homing switch debounce delay,milliseconds,Sets a short delay between phases of homing cycle to let a switch debounce.
|
||||||
|
27,Homing switch pull-off distance,millimeters,Retract distance after triggering switch to disengage it. Homing will fail if switch isn't cleared.
|
||||||
|
30,Maximum spindle speed,RPM,Maximum spindle speed. Sets PWM to 100% duty cycle.
|
||||||
|
31,Minimum spindle speed,RPM,Minimum spindle speed. Sets PWM to 0.4% or lowest duty cycle.
|
||||||
|
32,Laser-mode enable,boolean,Enables laser mode. Consecutive G1/2/3 commands will not halt when spindle speed is changed.
|
||||||
|
100,X-axis travel resolution,step/mm,X-axis travel resolution in steps per millimeter.
|
||||||
|
101,Y-axis travel resolution,step/mm,Y-axis travel resolution in steps per millimeter.
|
||||||
|
102,Z-axis travel resolution,step/mm,Z-axis travel resolution in steps per millimeter.
|
||||||
|
110,X-axis maximum rate,mm/min,X-axis maximum rate. Used as G0 rapid rate.
|
||||||
|
111,Y-axis maximum rate,mm/min,Y-axis maximum rate. Used as G0 rapid rate.
|
||||||
|
112,Z-axis maximum rate,mm/min,Z-axis maximum rate. Used as G0 rapid rate.
|
||||||
|
120,X-axis acceleration,mm/sec^2,X-axis acceleration. Used for motion planning to not exceed motor torque and lose steps.
|
||||||
|
121,Y-axis acceleration,mm/sec^2,Y-axis acceleration. Used for motion planning to not exceed motor torque and lose steps.
|
||||||
|
122,Z-axis acceleration,mm/sec^2,Z-axis acceleration. Used for motion planning to not exceed motor torque and lose steps.
|
||||||
|
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.
|
||||||
|
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.
|
||||||
|
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.
|
|
408
doc/log/commit_log_v1.1.txt
Normal file
408
doc/log/commit_log_v1.1.txt
Normal file
@ -0,0 +1,408 @@
|
|||||||
|
----------------
|
||||||
|
Date: 2016-10-12
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: Spindle speed bug fix.
|
||||||
|
|
||||||
|
- Spindle speed updating wasn’t working in the g-code parser due to
|
||||||
|
some borked up logic on my part. Fixed it and should be operating as
|
||||||
|
intended for both normal and laser spindle modes.
|
||||||
|
|
||||||
|
- Elaborated a little more on the new sleep mode in the documentation.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-10-11
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: v1.1c: New sleep mode. Laser mode and other bug fixes.
|
||||||
|
|
||||||
|
- New $SLP sleep mode that will disable spindle, coolant, and stepper
|
||||||
|
enable pins. Allows users to disable their steppers without having to
|
||||||
|
alter their settings. A reset is required to exit and re-initializes in
|
||||||
|
alarm state.
|
||||||
|
|
||||||
|
- Laser mode wasn’t updating the spindle PWM correctly (effected
|
||||||
|
spindle speed overrides) and not checking for modal states either.
|
||||||
|
Fixed both issues.
|
||||||
|
|
||||||
|
- While in laser mode, parking motions are ignored, since the power off
|
||||||
|
delay with the retract motion would burn the material. It will just
|
||||||
|
turn off and not move. A restore immediately powers up and resumes. No
|
||||||
|
delays.
|
||||||
|
|
||||||
|
- Changing rpm max and min settings did not update the spindle PWM
|
||||||
|
calculations. Now fixed.
|
||||||
|
|
||||||
|
- Increased default planner buffer from 16 to 17 block. It seems to be
|
||||||
|
stable, but need to monitor this carefully.
|
||||||
|
|
||||||
|
- Removed software debounce routine for limit pins. Obsolete.
|
||||||
|
|
||||||
|
- Fixed a couple parking motion bugs. One related to restoring
|
||||||
|
incorrectly and the other the parking rate wasn’t compatible with the
|
||||||
|
planner structs.
|
||||||
|
|
||||||
|
- Fixed a bug caused by refactoring the critical alarms in a recent
|
||||||
|
push. Soft limits weren’t invoking a critical alarm.
|
||||||
|
|
||||||
|
- Updated the documentation with the new sleep feature and added some
|
||||||
|
more details to the change summary.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-28
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: New jog cancel real-time command. Parser typo fix from last push.
|
||||||
|
|
||||||
|
- Added a new jog cancel real-time command. Rather than depending on a
|
||||||
|
feed hold to cancel a jogging motion, this realtime command can be used
|
||||||
|
instead. The main advantage is if a feed hold is used, you can
|
||||||
|
accidentally hold the machine right when Grbl returns to IDLE after
|
||||||
|
completing a jog. And the GUI doesn’t have to worry about tracking this
|
||||||
|
either.
|
||||||
|
|
||||||
|
- Fixed a typo in the g-code parser edits from the last push. Was
|
||||||
|
causing the G10 set coordinate system command to not work correctly.
|
||||||
|
|
||||||
|
- Updated the documentation with the jog cancel command.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-27
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: Refactored g-code parser. Saved 60bytes flash and some ram. Edited Readme.
|
||||||
|
|
||||||
|
- Freed up another 60 bytes of flash and 12-24 bytes of stack RAM by
|
||||||
|
using the pre-allocated IJK arc offset vector that is guaranteed to be
|
||||||
|
not in use. Only G10 and G28/30 require fetching from EEPROM and
|
||||||
|
retaining extra data. Both commands use axis words, which rules out
|
||||||
|
G2/3 arcs using IJK offsets existing in same block. Not ideal, but
|
||||||
|
every byte helps.
|
||||||
|
|
||||||
|
- Edited README.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-27
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: Update README and clarifications in jogging document.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-26
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: v1.1b: Tweaked Bf reports, jogging doc, saved another 160 bytes, minor bug fixes
|
||||||
|
|
||||||
|
- Increment to v1.1b due to status report tweak.
|
||||||
|
|
||||||
|
- Tweaked the buffer state status reports to show bytes and blocks
|
||||||
|
available, rather than in use. This does not require knowing the buffer
|
||||||
|
sizes beforehand. It’s implicit.
|
||||||
|
|
||||||
|
- Also, since buffer states are not used by most devs (after
|
||||||
|
inquiries), it is no longer enabled by default and a status mask option
|
||||||
|
was added for this.
|
||||||
|
|
||||||
|
- Fixed some typos and updated for the report tweak in the
|
||||||
|
documentation.
|
||||||
|
|
||||||
|
- Wrote a joystick implementation concept in the jogging markdown
|
||||||
|
document. Outlines how to get a low-latency feel to a joystick (and
|
||||||
|
other input devices).
|
||||||
|
|
||||||
|
- Removed XON/XOFF support. It’s not used by anyone because of its
|
||||||
|
inherent problems. Remains in older versions for reference.
|
||||||
|
|
||||||
|
- Added a compile option on how to handle the probe position during a
|
||||||
|
check mode.
|
||||||
|
|
||||||
|
- Fixed a jogging bug. If G93 is the modal state before a jogging
|
||||||
|
motion, the feed rate did not get calculated correctly. Fixed the issue.
|
||||||
|
|
||||||
|
- Refactored some code to save another 160+ bytes. Included an improved
|
||||||
|
float vector comparison macro and reducing a few large and repetitive
|
||||||
|
function calls.
|
||||||
|
|
||||||
|
- Fixed a probing bug (existing in v0.9 too) where the target positions
|
||||||
|
were not set correct and error handling was improper.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-25
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: Addressed much larger flash size with avr-gcc v4.9.2. Refactored reports to save 160KB.
|
||||||
|
|
||||||
|
- The newest Arduino IDE 1.6.12 has recently updated to avr-gcc v4.9.2.
|
||||||
|
Unfortunately, it produces a compiled size almost 0.7KB to 1KB larger
|
||||||
|
than prior versions! This can easily cause the base build to exceed the
|
||||||
|
Arduino Duemilanove/Nano flash limit of 30.5KB. The Arduino Uno seems
|
||||||
|
to be ok still with its 31.5KB flash limit.
|
||||||
|
|
||||||
|
- Makefile `-flto` compile flag added to cut down on the horrible flash
|
||||||
|
size when using the new avr-gcc. (Edit Makefile and remove comment on
|
||||||
|
COMPILE definition). This brings it in-line with what the IDE produces.
|
||||||
|
|
||||||
|
- Functionalized repetitive tasks in report.c to try to reduce overall
|
||||||
|
flash size. Successfully cut down about 160bytes.
|
||||||
|
|
||||||
|
- Removed printFloat_SettingValue() and printFloat_RPMValue()
|
||||||
|
functions. These aren’t required and can be replaced with a direct call
|
||||||
|
to printFloat() because they don’t require a unit conversion check.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-24
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: Serial RX count bug fix. Settings codes CSV. More documentation.
|
||||||
|
|
||||||
|
- Reverted back the serial RX count function to how it was. The
|
||||||
|
variable type was unsigned and cause an integer underflow whenever the
|
||||||
|
calculation produced a negative number. The old way was the correct way.
|
||||||
|
|
||||||
|
- Lots of minor edits to the code CSVs and markdown documents.
|
||||||
|
|
||||||
|
- Expanded on explaining feedback messages and startup line execution
|
||||||
|
feedback.
|
||||||
|
|
||||||
|
- Created a new settings codes CSV to help GUIs import the values and
|
||||||
|
meanings.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-22
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: Increment to v1.1a, minor compile bug fix, tweaked communication protocol, more docs.
|
||||||
|
|
||||||
|
- Incremented to v1.1a, rather than keep 1.0e. This is because there
|
||||||
|
are existing v1.0 installations. Don’t want to confuse people further.
|
||||||
|
|
||||||
|
- Certain version of the Arduino IDE did not like the `inline` in the
|
||||||
|
function header. Removed from spindle_control files to fix the problem.
|
||||||
|
|
||||||
|
- Tweaked the communication protocol slightly. Added message type
|
||||||
|
indicators for all `[]`bracketed feedback messages. It’s been
|
||||||
|
problematic for GUI dev to try to determine the context of a message
|
||||||
|
and how it should be handled. These indictors should help tremendously
|
||||||
|
to remove context all together.
|
||||||
|
|
||||||
|
- Also altered how `$N` startup lines are presented when executed. They
|
||||||
|
now start with an open chevron ‘>’ followed by the line and an ‘:ok’ to
|
||||||
|
indicate it executed. The ‘ok’ is on the same line intentionally so it
|
||||||
|
doesn’t mess up a streaming protocol counter.
|
||||||
|
|
||||||
|
- Managed to save a 100+KB from refactoring parts of report.c. (Thanks
|
||||||
|
Vasilis!) Freed up room to alter the protocol a little.
|
||||||
|
|
||||||
|
- Wrote a markdown document on interface messaging to make it clear how
|
||||||
|
it’s intended to work. See interface.md in /doc/markdown
|
||||||
|
|
||||||
|
- Started to pull in some Wiki pages from the old grbl site and
|
||||||
|
beginning to update them for v1.1.
|
||||||
|
|
||||||
|
- Created new commit log for v1.1.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-22
|
||||||
|
Author: Sonny Jeon
|
||||||
|
Subject: Merge pull request #1 from winder/dev
|
||||||
|
|
||||||
|
Add locale to code CSVs.
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-22
|
||||||
|
Author: winder
|
||||||
|
Subject: Add locale to code CSVs.
|
||||||
|
|
||||||
|
|
||||||
|
----------------
|
||||||
|
Date: 2016-09-21
|
||||||
|
Author: chamnit
|
||||||
|
Subject: Grbl v1.0e huge beta release. Overrides and new reporting.
|
||||||
|
|
||||||
|
- Feature: Realtime feed, rapid, and spindle speed overrides. These
|
||||||
|
alter the running machine state within tens of milliseconds!
|
||||||
|
- Feed override: 100%, +/-10%, +/-1% commands with values 1-200% of
|
||||||
|
programmed feed
|
||||||
|
- Rapid override: 100%, 50%, 25% rapid rate commands
|
||||||
|
- Spindle speed override: 100%, +/-10%, +/-1% commands with values
|
||||||
|
50-200% of programmed speed
|
||||||
|
- Override values have configurable limits and increments in
|
||||||
|
config.h.
|
||||||
|
- Feature: Realtime toggle overrides for spindle stop, flood coolant,
|
||||||
|
and optionally mist coolant
|
||||||
|
- Spindle stop: Enables and disables spindle during a feed hold.
|
||||||
|
Automatically restores last spindles state.
|
||||||
|
- Flood and mist coolant: Immediately toggles coolant state until
|
||||||
|
next toggle or g-code coolant command.
|
||||||
|
- Feature: Jogging mode! Incremental and absolute modes supported.
|
||||||
|
- Grbl accepts jogging-specific commands like $J=X100F50. An axis
|
||||||
|
word and feed rate are required. G20/21 and G90/G91 commands are
|
||||||
|
accepted.
|
||||||
|
- Jog motions can be canceled at any time by a feed hold `!`
|
||||||
|
command. The buffer is automatically flushed. (No resetting required).
|
||||||
|
- Jog motions do not alter the g-code parser state so GUIs don’t
|
||||||
|
have to track what they changed and correct it.
|
||||||
|
- Feature: Laser mode setting. Allows Grbl to execute continuous
|
||||||
|
motions with spindle speed and state changes.
|
||||||
|
- Feature: Significantly improved status reports. Overhauled to cram in
|
||||||
|
more meaningful data and still make it smaller on average.
|
||||||
|
- All available data is now sent by default, but does not appear if
|
||||||
|
it doesn’t change or is not active.
|
||||||
|
- Machine position(MPos) or work position(WPos) is reported but not
|
||||||
|
both at the same time. Instead, the work coordinate offsets (WCO)are
|
||||||
|
sent intermittently whenever it changes or refreshes after 10-30 status
|
||||||
|
reports. Position vectors are easily computed by WPos = MPos - WCO.
|
||||||
|
- All data has changed in some way. Details of changes are in the
|
||||||
|
markdown documents and wiki.
|
||||||
|
- Feature: 16 new realtime commands to control overrides. All in
|
||||||
|
extended-ASCII character space.
|
||||||
|
- While they are not easily typeable and requires a GUI, they can’t
|
||||||
|
be accidentally triggered by some latent character in the g-code
|
||||||
|
program and have tons of room for expansion.
|
||||||
|
- Feature: New substates for HOLD and SAFETY DOOR. A `:x` is appended
|
||||||
|
to the state, where `x` is an integer and indicates a substate.
|
||||||
|
- For example, each integer of a door state describes in what phase
|
||||||
|
the machine is in during parking. Substates are detailed in the
|
||||||
|
documentation.
|
||||||
|
- Feature: With the alarm codes, homing and probe alarms have been
|
||||||
|
expanded with more codes to provide more exact feedback on what caused
|
||||||
|
the alarm.
|
||||||
|
- Feature: New hard limit check upon power-up or reset. If detected, a
|
||||||
|
feedback message to check the limit switches sent immediately after the
|
||||||
|
welcome message.
|
||||||
|
- May be disabled in config.h.
|
||||||
|
|
||||||
|
- OEM feature: Enable/disable `$RST=` individual commands based on
|
||||||
|
desired behavior in config.h.
|
||||||
|
- OEM feature: Configurable EEPROM wipe to prevent certain data from
|
||||||
|
being deleted during firmware upgrade to a new settings version or
|
||||||
|
`RST=*` command.
|
||||||
|
- OEM feature: Enable/disable the `$I=` build info write string with
|
||||||
|
external EEPROM write example sketch.
|
||||||
|
- This prevents a user from altering the build info string in
|
||||||
|
EEPROM. This requires the vendor to write the string to EEPROM via
|
||||||
|
external means. An Arduino example sketch is provided to accomplish
|
||||||
|
this. This would be useful for contain product data that is
|
||||||
|
retrievable.
|
||||||
|
|
||||||
|
- Tweak: All feedback has been drastically trimmed to free up flash
|
||||||
|
space for the v1.0 release.
|
||||||
|
- The `$` help message is just one string, listing available
|
||||||
|
commands.
|
||||||
|
- The `$$` settings printout no longer includes descriptions. Only
|
||||||
|
the setting values. (Sorry it’s this or remove overrides!)
|
||||||
|
- Grbl `error:` and `ALARM:` responses now only contain codes. No
|
||||||
|
descriptions. All codes are explained in documentation.
|
||||||
|
- Grbl’s old feedback style may be restored via a config.h, but
|
||||||
|
keep in mind that it will likely not fit into the Arduino’s flash space.
|
||||||
|
- Tweak: Grbl now forces a buffer sync or stop motion whenever a g-code
|
||||||
|
command needs to update and write a value to EEPROM or changes the work
|
||||||
|
coordinate offset.
|
||||||
|
- This addresses two old issues in all prior Grbl versions. First,
|
||||||
|
an EEPROM write requires interrupts to be disabled, including stepper
|
||||||
|
and serial comm. Steps can be lost and data can be corrupted. Second,
|
||||||
|
the work position may not be correlated to the actual machine position,
|
||||||
|
since machine position is derived from the actual current execution
|
||||||
|
state, while work position is based on the g-code parser offset state.
|
||||||
|
They are usually not in sync and the parser state is several motions
|
||||||
|
behind. This forced sync ensures work and machine positions are always
|
||||||
|
correct.
|
||||||
|
- This behavior can be disabled through a config.h option, but it’s
|
||||||
|
not recommended to do so.
|
||||||
|
- Tweak: To make status reports standardized, users can no longer
|
||||||
|
change what is reported via status report mask, except for only
|
||||||
|
toggling machine or work positions.
|
||||||
|
- All other data fields are included in the report and can only be
|
||||||
|
disabled through the config.h file. It’s not recommended to alter this,
|
||||||
|
because GUIs will be expecting this data to be present and may not be
|
||||||
|
compatible.
|
||||||
|
- Tweak: Homing cycle and parking motion no longer report a negative
|
||||||
|
line number in a status report. These will now not report a line number
|
||||||
|
at all.
|
||||||
|
- Tweak: New `[Restoring spindle]` message when restoring from a
|
||||||
|
spindle stop override. Provides feedback what Grbl is doing while the
|
||||||
|
spindle is powering up and a 4.0 second delay is enforced.
|
||||||
|
- Tweak: Override values are reset to 100% upon M2/30. This behavior
|
||||||
|
can be disabled in config.h
|
||||||
|
- Tweak: The planner buffer size has been reduced from 18 to 16 to free
|
||||||
|
up RAM for tracking and controlling overrides.
|
||||||
|
- Tweak: TX buffer size has been increased from 64 to 90 bytes to
|
||||||
|
improve status reporting and overall performance.
|
||||||
|
- Tweak: Removed the MOTION CANCEL state. It was redundant and didn’t
|
||||||
|
affect Grbl’s overall operation by doing so.
|
||||||
|
- Tweak: Grbl’s serial buffer increased by +1 internally, such that 128
|
||||||
|
bytes means 128, not 127 due to the ring buffer implementation. Long
|
||||||
|
overdue.
|
||||||
|
- Tweak: Altered sys.alarm variable to be set by alarm codes, rather
|
||||||
|
than bit flags. Simplified how it worked overall.
|
||||||
|
- Tweak: Planner buffer and serial RX buffer usage has been combined in
|
||||||
|
the status reports.
|
||||||
|
- Tweak: Pin state reporting has been refactored to report only the
|
||||||
|
pins “triggered” and nothing when not “triggered”.
|
||||||
|
- Tweak: Current machine rate or speed is now included in every report.
|
||||||
|
- Tweak: The work coordinate offset (WCO) and override states only need
|
||||||
|
to be refreshed intermittently or reported when they change. The
|
||||||
|
refresh rates may be altered for each in the config.h file with
|
||||||
|
different idle and busy rates to lessen Grbl’s load during a job.
|
||||||
|
- Tweak: For temporary compatibility to existing GUIs until they are
|
||||||
|
updated, an option to revert back to the old style status reports is
|
||||||
|
available in config.h, but not recommended for long term use.
|
||||||
|
- Tweak: Removed old limit pin state reporting option from config.h in
|
||||||
|
lieu of new status report that includes them.
|
||||||
|
- Tweak: Updated the defaults.h file to include laser mode, altered
|
||||||
|
status report mask, and fix an issue with a missing invert probe pin
|
||||||
|
default.
|
||||||
|
|
||||||
|
- Refactor: Changed how planner line data is generated and passed to
|
||||||
|
the planner and onto the step generator. By making it a struct
|
||||||
|
variable, this saved significant flash space.
|
||||||
|
- Refactor: Major re-factoring of the planner to incorporate override
|
||||||
|
values and allow for re-calculations fast enough to immediately take
|
||||||
|
effect during operation. No small feat.
|
||||||
|
- Refactor: Re-factored the step segment generator for re-computing new
|
||||||
|
override states.
|
||||||
|
- Refactor: Re-factored spindle_control.c to accommodate the spindle
|
||||||
|
speed overrides and laser mode.
|
||||||
|
- Refactor: Re-factored parts of the codebase for a new jogging mode.
|
||||||
|
Still under development though and slated to be part of the official
|
||||||
|
v1.0 release. Hang tight.
|
||||||
|
- Refactor: Created functions for computing a unit vector and value
|
||||||
|
limiting based on axis maximums to free up more flash.
|
||||||
|
- Refactor: The spindle PWM is now set directly inside of the stepper
|
||||||
|
ISR as it loads new step segments.
|
||||||
|
- Refactor: Moved machine travel checks out of soft limits function
|
||||||
|
into its own since jogging uses this too.
|
||||||
|
- Refactor: Removed coolant_stop() and combined with
|
||||||
|
coolant_set_state().
|
||||||
|
- Refactor: The serial RX ISR forks off extended ASCII values to
|
||||||
|
quickly assess the new override realtime commands.
|
||||||
|
- Refactor: Altered some names of the step control flags.
|
||||||
|
- Refactor: Improved efficiency of the serial RX get buffer count
|
||||||
|
function.
|
||||||
|
- Refactor: Saved significant flash by removing and combining print
|
||||||
|
functions. Namely the uint8 base10 and base2 functions.
|
||||||
|
- Refactor: Moved the probe state check in the main stepper ISR to
|
||||||
|
improve its efficiency.
|
||||||
|
- Refactor: Single character printPgmStrings() went converted to direct
|
||||||
|
serial_write() commands to save significant flash space.
|
||||||
|
|
||||||
|
- Documentation: Detailed Markdown documents on error codes, alarm
|
||||||
|
codes, messages, new real-time commands, new status reports, and how
|
||||||
|
jogging works. More to come later and will be posted on the Wiki as
|
||||||
|
well.
|
||||||
|
- Documentation: CSV files for quick importing of Grbl error and alarm
|
||||||
|
codes.
|
||||||
|
|
||||||
|
- Bug Fix: Applied v0.9 master fixes to CoreXY homing.
|
||||||
|
- Bug Fix: The print float function would cause Grbl to crash if a
|
||||||
|
value was 1e6 or greater. Increased the buffer by 3 bytes to help
|
||||||
|
prevent this in the future.
|
||||||
|
- Bug Fix: Build info and startup string EEPROM restoring was not
|
||||||
|
writing the checksum value.
|
||||||
|
- Bug Fix: Corrected an issue with safety door restoring the proper
|
||||||
|
spindle and coolant state. It worked before, but breaks with laser mode
|
||||||
|
that can continually change spindle state per planner block.
|
||||||
|
- Bug Fix: Move system position and probe position arrays out of the
|
||||||
|
system_t struct. Ran into some compiling errors that were hard to track
|
||||||
|
down as to why. Moving them out fixed it.
|
||||||
|
|
106
doc/markdown/change_summary.md
Normal file
106
doc/markdown/change_summary.md
Normal file
@ -0,0 +1,106 @@
|
|||||||
|
### _Grbl v1.1 - Change Summary_
|
||||||
|
|
||||||
|
--------
|
||||||
|
|
||||||
|
### _Specific details are available in the other markdown documents._
|
||||||
|
--------
|
||||||
|
|
||||||
|
#### GUI Interface Tweaks from Grbl v0.9
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
- `ok` / `error:x` : Normal send command and execution response acknowledgement. Used for streaming.
|
||||||
|
|
||||||
|
- `< >` : Enclosed chevrons contains status report data.
|
||||||
|
|
||||||
|
- `Grbl X.Xx ['$' for help]` : Welcome message indicates initialization.
|
||||||
|
|
||||||
|
- `ALARM:x` : Indicates an alarm has been thrown. Grbl is now in an alarm state.
|
||||||
|
|
||||||
|
- `$x=val` and `$Nx=line` indicate a settings printout from a `$` and `$N` user query, respectively.
|
||||||
|
|
||||||
|
- `[MSG:]` : Indicates a non-queried feedback message.
|
||||||
|
|
||||||
|
- `[GC:]` : Indicates a queried `$G` g-code state message.
|
||||||
|
|
||||||
|
- `[HLP:]` : Indicates the help message.
|
||||||
|
|
||||||
|
- `[G54:]`, `[G55:]`, `[G56:]`, `[G57:]`, `[G58:]`, `[G59:]`, `[G28:]`, `[G30:]`, `[G92:]`, `[TLO:]`, and `[PRB:]` messages indicate the parameter data printout from a `$#` user query.
|
||||||
|
|
||||||
|
- `[VER:]` : Indicates build info and string from a `$I` user query.
|
||||||
|
|
||||||
|
- `[echo:]` : Indicates an automated line echo from a pre-parsed string prior to g-code parsing. Enabled by config.h option.
|
||||||
|
|
||||||
|
- `>G54G20:ok` : The open chevron indicates startup line execution. The `:ok` suffix shows it executed correctly without adding an unmatched `ok` response on a new line.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
----
|
||||||
|
|
||||||
|
#### Realtime Status Reports Changes from Grbl v0.9
|
||||||
|
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
- Data fields are separated by `|` pipe delimiters, rather than `,` commas that were used to separate data values. This should help with parsing.
|
||||||
|
|
||||||
|
- 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.
|
||||||
|
- All available data is always sent to standardize the reports across all GUIs.
|
||||||
|
- For unique situations, data fields can be removed by config.h macros, but it is highly recommended to not alter these.
|
||||||
|
|
||||||
|
|
||||||
|
- `MPos:` OR `WPos:` are always included in a report, but not BOTH at the same time.
|
||||||
|
|
||||||
|
- This reduces transmit overhead tremendously by removing upwards to 40 characters.
|
||||||
|
- `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.
|
||||||
|
- `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.
|
||||||
|
- `WCO:` is simply the sum of the work coordinate system, G92, and G43.1 tool length offsets.
|
||||||
|
- Basically, a GUI just needs to retain the last `WCO:` and apply the equation to get the other position vector.
|
||||||
|
- `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.
|
||||||
|
- Be aware of the following issue regarding `WPos:`.
|
||||||
|
- 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.
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
|
||||||
|
- The `Hold` and `Door` states includes useful sub-state info via a `:` colon delimiter and an integer value. See descriptions for details.
|
||||||
|
|
||||||
|
- Limit and other input pin reports have significantly changed to reduce transmit overhead.
|
||||||
|
- The data type description is now just `Pn:`, rather than `Lim:000` or `Pin:000|0|0000`
|
||||||
|
- It does not appear if no inputs are detected as triggered.
|
||||||
|
- 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.
|
||||||
|
- For example, a triggered Z-limit and probe pin would report `Pn:ZP`.
|
||||||
|
|
||||||
|
|
||||||
|
- Buffer data (planner and serial RX) reports have been tweaked and combined.
|
||||||
|
|
||||||
|
- `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.
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
|
||||||
|
- Override reports are intermittent since they don't change often once set.
|
||||||
|
|
||||||
|
- 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.
|
||||||
|
- There are two override fields:
|
||||||
|
- `Ov:100,100,100` Organized as feed, rapid, and spindle speed overrides in percent.
|
||||||
|
- `T:SFM` with each letter `S`, `F`, and `M` are defined as spindle stop active, flood coolant toggled, and mist coolant toggled, respectively.
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
- Line numbers, when enabled in config.h, are omitted when:
|
||||||
|
|
||||||
|
- No line number is passed to Grbl in a block.
|
||||||
|
- Grbl is performing a system motion like homing, jogging, or parking.
|
||||||
|
- Grbl is executing g-code block that does not contain a motion, like `G20G54` or `G4P1` dwell. (NOTE: Looking to fixing this later.)
|
||||||
|
|
||||||
|
-------
|
||||||
|
|
||||||
|
#### New Commands
|
||||||
|
|
||||||
|
- `$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.
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
- `$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.
|
||||||
|
|
||||||
|
- 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.
|
||||||
|
- NOTE: Parking motions are automatically disabled when laser mode is enabled to prevent burning.
|
581
doc/markdown/interface.md
Normal file
581
doc/markdown/interface.md
Normal file
@ -0,0 +1,581 @@
|
|||||||
|
# Grbl Interface Basics
|
||||||
|
|
||||||
|
The interface for Grbl is fairly simple and straightforward. With Grbl v1.1, steps have been taken to try to make it even easier for new users to get started, and for GUI developers to write their own custom interfaces to Grbl.
|
||||||
|
|
||||||
|
In short, Grbl communicates through the serial interface on the Arduino. You just need to connect your Arduino to your computer with a USB cable. Use any standard serial terminal program to connect to Grbl, such as: the Arduino IDE serial monitor, Coolterm, puTTY, etc. Or use one of the many great Grbl GUIs out there in the Internet wild.
|
||||||
|
|
||||||
|
Just about every user interaction with Grbl is performed by sending it a string of characters, followed by a carriage return. Grbl will then process the string, execute it accordingly, and then reply back with a response message to tell you how it went. These strings include sending Grbl: a G-code block to execute, commands to configure Grbl's system settings, to view how Grbl is doing, etc. At times, Grbl may not respond immediately. This happens only when Grbl is busy doing something else, or waiting for some room to clear in its look-ahead planner buffer so it can finish processing the previous line sent.
|
||||||
|
|
||||||
|
In other words, both commands sent to Grbl and messages received from Grbl have a format of a single line of characters, terminated by a return. To provide more feedback on what Grbl is doing, additional messages may be "pushed" from Grbl to the user in response to a query or to let the user know something important just happened. Finally, an exception to the command and response interface are Grbl's real-time commands. These commands are single, special characters that may be sent to Grbl at any time to immediately alter or report what its doing and do not have a response message. See the [realtime commands] document to see what they are and how they work.
|
||||||
|
|
||||||
|
|
||||||
|
#### Start Up Message
|
||||||
|
|
||||||
|
**`Grbl X.Xx ['$' for help]`**
|
||||||
|
|
||||||
|
The start up message always prints upon startup and after a reset. Whenever you see this message, this also means that Grbl has completed re-initializing all its systems, so everything starts out the same every time you use Grbl.
|
||||||
|
|
||||||
|
* `X.Xx` indicates the major version number, followed by a minor version letter. The major version number indicates the general release, while the letter simply indicates a feature update or addition from the preceding minor version letter.
|
||||||
|
* Bug fix revisions are tracked by the build info version number, printed when an `$I` command is sent. These revisions don't update the version number and are given by date revised in year, month, and day, like so `20160820`.
|
||||||
|
|
||||||
|
#### Grbl `$` Help Message
|
||||||
|
|
||||||
|
Every string Grbl receives is assumed to be a G-code block/line for it to execute, except for some special system commands Grbl uses for configuration, provide feedback to the user on what and how it's doing, or perform some task such as a homing cycle. To see a list of these system commands, type `$` followed by an enter, and Grbl will respond with:
|
||||||
|
|
||||||
|
```
|
||||||
|
[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H ~ ! ? ctrl-x]
|
||||||
|
```
|
||||||
|
|
||||||
|
- _**NOTE:** Grbl v1.1's new override real-time commands are not included in the help message. They use the extended-ASCII character set, which are not easily type-able, and require a GUI that supports them. This is for two reasons: Establish enough characters for all of the overrides with extra for later growth, and prevent accidental keystrokes or characters in a g-code file from enacting an override inadvertently. _
|
||||||
|
|
||||||
|
* Check out our [Configuring Grbl](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9) wiki page to find out what all of these commands mean and how to use them.
|
||||||
|
|
||||||
|
|
||||||
|
---------
|
||||||
|
|
||||||
|
# Grbl Response Messages
|
||||||
|
|
||||||
|
Every G-code block sent to Grbl and Grbl `$` system command that is terminated with a return will be parsed and processed by Grbl. Grbl will then respond either if it recognized the command with an `ok` line or if there was a problem with an `error` line.
|
||||||
|
|
||||||
|
* **`ok`**: All is good! Everything in the last line was understood by Grbl and was successfully processed and executed.
|
||||||
|
|
||||||
|
- If an empty line with only a return is sent to Grbl, it considers it a valid line and will return an `ok` too, except it didn't do anything.
|
||||||
|
|
||||||
|
|
||||||
|
* **`error:X`**: Something went wrong! Grbl did not recognize the command and did not execute anything inside that message. The `X` is given as a numeric error code to tell you exactly what happened. The table below decribes every one of them.
|
||||||
|
|
||||||
|
| ID | Error Code Description |
|
||||||
|
|:-------------:|----|
|
||||||
|
| **`1`** | G-code words consist of a letter and a value. Letter was not found. |
|
||||||
|
| **`2`** | Numeric value format is not valid or missing an expected value. |
|
||||||
|
| **`3`** | Grbl '$' system command was not recognized or supported. |
|
||||||
|
| **`4`** | Negative value received for an expected positive value. |
|
||||||
|
| **`5`** | Homing cycle is not enabled via settings. |
|
||||||
|
| **`6`** | Minimum step pulse time must be greater than 3usec |
|
||||||
|
| **`7`** | EEPROM read failed. Reset and restored to default values. |
|
||||||
|
| **`8`** | Grbl '$' command cannot be used unless Grbl is IDLE. Ensures smooth operation during a job. |
|
||||||
|
| **`9`** | G-code locked out during alarm or jog state |
|
||||||
|
| **`10`** | Soft limits cannot be enabled without homing also enabled. |
|
||||||
|
| **`11`** | Max characters per line exceeded. Line was not processed and executed. |
|
||||||
|
| **`12`** | (Compile Option) Grbl '$' setting value exceeds the maximum step rate supported. |
|
||||||
|
| **`13`** | Safety door detected as opened and door state initiated. |
|
||||||
|
| **`14`** | (Grbl-Mega Only) Build info or startup line exceeded EEPROM line length limit. |
|
||||||
|
| **`15`** | Jog target exceeds machine travel. Command ignored. |
|
||||||
|
| **`16`** | Jog command with no '=' or contains prohibited g-code. |
|
||||||
|
| **`20`** | Unsupported or invalid g-code command found in block. |
|
||||||
|
| **`21`** | More than one g-code command from same modal group found in block.|
|
||||||
|
| **`22`** | Feed rate has not yet been set or is undefined. |
|
||||||
|
| **`23`** | G-code command in block requires an integer value. |
|
||||||
|
| **`24`** | Two G-code commands that both require the use of the `XYZ` axis words were detected in the block.|
|
||||||
|
| **`25`** | A G-code word was repeated in the block.|
|
||||||
|
| **`26`** | A G-code command implicitly or explicitly requires `XYZ` axis words in the block, but none were detected.|
|
||||||
|
| **`27`**| `N` line number value is not within the valid range of `1` - `9,999,999`. |
|
||||||
|
| **`28`** | A G-code command was sent, but is missing some required `P` or `L` value words in the line. |
|
||||||
|
| **`29`** | Grbl supports six work coordinate systems `G54-G59`. `G59.1`, `G59.2`, and `G59.3` are not supported.|
|
||||||
|
| **`30`**| The `G53` G-code command requires either a `G0` seek or `G1` feed motion mode to be active. A different motion was active.|
|
||||||
|
| **`31`** | There are unused axis words in the block and `G80` motion mode cancel is active.|
|
||||||
|
| **`32`** | A `G2` or `G3` arc was commanded but there are no `XYZ` axis words in the selected plane to trace the arc.|
|
||||||
|
| **`33`** | The motion command has an invalid target. `G2`, `G3`, and `G38.2` generates this error, if the arc is impossible to generate or if the probe target is the current position.|
|
||||||
|
| **`34`** | A `G2` or `G3` arc, traced with the radius definition, had a mathematical error when computing the arc geometry. Try either breaking up the arc into semi-circles or quadrants, or redefine them with the arc offset definition.|
|
||||||
|
| **`35`** | A `G2` or `G3` arc, traced with the offset definition, is missing the `IJK` offset word in the selected plane to trace the arc.|
|
||||||
|
| **`36`** | There are unused, leftover G-code words that aren't used by any command in the block.|
|
||||||
|
| **`37`** | The `G43.1` dynamic tool length offset command cannot apply an offset to an axis other than its configured axis. The Grbl default axis is the Z-axis.|
|
||||||
|
|
||||||
|
|
||||||
|
----------------------
|
||||||
|
|
||||||
|
# Grbl Push Messages
|
||||||
|
|
||||||
|
Along with the response message to indicate successfully executing a line command sent to Grbl, Grbl provides additional push messages for important feedback of its current state or if something went horribly wrong. These messages are "pushed" from Grbl and may appear at anytime. They are usually in response to a user query or some system event that Grbl needs to tell you about immediately. These push messages are organized into five general classes:
|
||||||
|
|
||||||
|
- **_ALARM messages_** - Means an emergency mode has been enacted and shut down normal use.
|
||||||
|
|
||||||
|
- **_'$' settings messages_** - Contains the type and data value for a Grbl setting.
|
||||||
|
|
||||||
|
- **_Feedback messages_** - Contains general feedback and can provide useful data.
|
||||||
|
|
||||||
|
- **_Startup line execution_** - Indicates a startup line as executed with the line itself and how it went.
|
||||||
|
|
||||||
|
- **_Real-time status reports_** - Contains current run data like state, position, and speed.
|
||||||
|
|
||||||
|
|
||||||
|
------
|
||||||
|
|
||||||
|
#### Alarm Message
|
||||||
|
|
||||||
|
Alarm is an emergency state. Something has gone terribly wrong when these occur. Typically, they are caused by limit error when the machine has moved or wants to move outside the machine travel and crash into the ends. They also report problems if Grbl is lost and can't guarantee positioning or a probe command has failed. Once in alarm-mode, Grbl will lock out all g-code functionality and accept only a small set of commands. It may even stop everything and force you to acknowledge the problem until you issue Grbl a reset. While in alarm-mode, the user can override the alarm manually with a specific command, which then re-enables g-code so you can move the machine again. This ensures the user knows about the problem and has taken steps to fix or account for it.
|
||||||
|
|
||||||
|
Similar to error messages, all alarm messages are sent as **`ALARM:X`**, where `X` is an alarm code to tell you exacly what caused the alarm. The table below describes the meaning of each alarm code.
|
||||||
|
|
||||||
|
| ID | Alarm Code Description |
|
||||||
|
|:-------------:|----|
|
||||||
|
| **`1`** | Hard limit triggered. Machine position is likely lost due to sudden and immediate halt. Re-homing is highly recommended. |
|
||||||
|
| **`2`** | G-code motion target exceeds machine travel. Machine position safely retained. Alarm may be unlocked. |
|
||||||
|
| **`3`** | Reset while in motion. Grbl cannot guarantee position. Lost steps are likely. Re-homing is highly recommended. |
|
||||||
|
| **`4`** | Probe fail. The probe is not in the expected initial state before starting probe cycle, where G38.2 and G38.3 is not triggered and G38.4 and G38.5 is triggered. |
|
||||||
|
| **`5`** | Probe fail. Probe did not contact the workpiece within the programmed travel for G38.2 and G38.4. |
|
||||||
|
| **`6`** | Homing fail. Reset during active homing cycle. |
|
||||||
|
| **`7`** | Homing fail. Safety door was opened during active homing cycle. |
|
||||||
|
| **`8`** | Homing fail. Cycle failed to clear limit switch when pulling off. Try increasing pull-off setting or check wiring. |
|
||||||
|
| **`9`** | Homing fail. Could not find limit switch within search distance. Defined as `1.5 * max_travel` on search and `5 * pulloff` on locate phases. |
|
||||||
|
|
||||||
|
-------
|
||||||
|
|
||||||
|
#### Grbl `$` Settings Message
|
||||||
|
|
||||||
|
When a push message starts with a `$`, this indicates Grbl is sending a setting and its configured value. There are only two types of settings messages: a single setting and value `$x=val` and a startup string setting `$Nx=line`. See [Configuring Grbl v1.x] document if you'd like to learn how to write these values for your machine.
|
||||||
|
|
||||||
|
- `$x=val` will only appear when the user queries to print all of Grbl's settings via the `$$` print settings command. It does so sequentially and completes with an `ok`.
|
||||||
|
|
||||||
|
- In prior versions of Grbl, the `$` settings included a short description of the setting immediately after the value. However, due to flash restrictions, most human-readable strings were removed to free up flash for the new override features in Grbl v1.1. In short, it was these strings or overrides, and overrides won. Keep in mind that once these values are set, they usually don't change, and GUIs will likely provide the assistance of translating these codes for users.
|
||||||
|
|
||||||
|
- _**NOTE for GUI developers:**_ _As with the error and alarm codes, settings codes are available in an easy to parse CSV file in the `/doc/csv` folder. These are continually updated._
|
||||||
|
|
||||||
|
- The `$$` settings print out is shown below and the following describes each setting.
|
||||||
|
|
||||||
|
```
|
||||||
|
$0=10
|
||||||
|
$1=25
|
||||||
|
$2=0
|
||||||
|
$3=0
|
||||||
|
$4=0
|
||||||
|
$5=0
|
||||||
|
$6=0
|
||||||
|
$10=255
|
||||||
|
$11=0.010
|
||||||
|
$12=0.002
|
||||||
|
$13=0
|
||||||
|
$20=0
|
||||||
|
$21=0
|
||||||
|
$22=0
|
||||||
|
$23=0
|
||||||
|
$24=25.000
|
||||||
|
$25=500.000
|
||||||
|
$26=250
|
||||||
|
$27=1.000
|
||||||
|
$30=1000.
|
||||||
|
$31=0.
|
||||||
|
$32=0
|
||||||
|
$100=250.000
|
||||||
|
$101=250.000
|
||||||
|
$102=250.000
|
||||||
|
$110=500.000
|
||||||
|
$111=500.000
|
||||||
|
$112=500.000
|
||||||
|
$120=10.000
|
||||||
|
$121=10.000
|
||||||
|
$122=10.000
|
||||||
|
$130=200.000
|
||||||
|
$131=200.000
|
||||||
|
$132=200.000
|
||||||
|
ok
|
||||||
|
```
|
||||||
|
|
||||||
|
| `$x` Code | Setting Description, Units |
|
||||||
|
|:-------------:|----|
|
||||||
|
| **`0`** | Step pulse time, microseconds |
|
||||||
|
| **`1`** | Step idle delay, milliseconds |
|
||||||
|
| **`2`** | Step pulse invert, mask |
|
||||||
|
| **`3`** | Step direction invert, mask |
|
||||||
|
| **`4`** | Invert step enable pin, boolean |
|
||||||
|
| **`5`** | Invert limit pins, boolean |
|
||||||
|
| **`6`** | Invert probe pin, boolean |
|
||||||
|
| **`10`** | Status report options, mask |
|
||||||
|
| **`11`** | Junction deviation, millimeters |
|
||||||
|
| **`12`** | Arc tolerance, millimeters |
|
||||||
|
| **`13`** | Report in inches, boolean |
|
||||||
|
| **`20`** | Soft limits enable, boolean |
|
||||||
|
| **`21`** | Hard limits enable, boolean |
|
||||||
|
| **`22`** | Homing cycle enable, boolean |
|
||||||
|
| **`23`** | Homing direction invert, mask |
|
||||||
|
| **`24`** | Homing locate feed rate, mm/min |
|
||||||
|
| **`25`** | Homing search seek rate, mm/min |
|
||||||
|
| **`26`** | Homing switch debounce delay, milliseconds |
|
||||||
|
| **`27`** | Homing switch pull-off distance, millimeters |
|
||||||
|
| **`30`** | Maximum spindle speed, RPM |
|
||||||
|
| **`31`** | Minimum spindle speed, RPM |
|
||||||
|
| **`32`** | Laser-mode enable, boolean |
|
||||||
|
| **`100`** | X-axis steps per millimeter |
|
||||||
|
| **`101`** | Y-axis steps per millimeter |
|
||||||
|
| **`102`** | Z-axis steps per millimeter |
|
||||||
|
| **`110`** | X-axis maximum rate, mm/min |
|
||||||
|
| **`111`** | Y-axis maximum rate, mm/min |
|
||||||
|
| **`112`** | Z-axis maximum rate, mm/min |
|
||||||
|
| **`120`** | X-axis acceleration, mm/sec^2 |
|
||||||
|
| **`121`** | Y-axis acceleration, mm/sec^2 |
|
||||||
|
| **`122`** | Z-axis acceleration, mm/sec^2 |
|
||||||
|
| **`130`** | X-axis maximum travel, millimeters |
|
||||||
|
| **`131`** | Y-axis maximum travel, millimeters |
|
||||||
|
| **`132`** | Z-axis maximum travel, millimeters |
|
||||||
|
|
||||||
|
|
||||||
|
- The other `$Nx=line` message is the print-out of a user-defined startup line, where `x` denotes the startup line order and ranges from `0` to `1` by default. The `line` denotes the startup line to be executed by Grbl upon reset or power-up, except during an ALARM.
|
||||||
|
|
||||||
|
- When a user queries for the startup lines via a `$N` command, the following is sent by Grbl and completed by an `ok` response. The first line sets the initial startup work coordinate system to `G54`, while the second line is empty and does not execute.
|
||||||
|
```
|
||||||
|
$N0=G54
|
||||||
|
$N1=
|
||||||
|
ok
|
||||||
|
```
|
||||||
|
|
||||||
|
|
||||||
|
------
|
||||||
|
|
||||||
|
#### Feedback Messages
|
||||||
|
|
||||||
|
Feedback messages provide non-critical information on what Grbl is doing, what it needs, and/or provide some non-real-time data for the user when queried. Not too complicated. Feedback message are always enclosed in `[]` brackets, except for the startup line execution message which begins with an open chevron character `>`.
|
||||||
|
|
||||||
|
- **Non-Queried Feedback Messages:** These feedback messages that may appear at any time and is not part of a query are listed and described below. They are usually sent as an additional helpful acknowledgement of some event or command executed. These always start with a `[MSG:` to denote their type.
|
||||||
|
|
||||||
|
- `[MSG:Reset to continue]` - Critical event message. Reset is required before Grbl accepts any other commands. This prevents ongoing command streaming and risking a motion before the alarm is acknowledged. Only hard or soft limit errors send this message immediately after the ALARM:x code.
|
||||||
|
|
||||||
|
- `[MSG:‘$H’|’$X’ to unlock]`- Alarm state is active at initialization. This message serves as a reminder note on how to cancel the alarm state. All g-code commands and some ‘$’ are blocked until the alarm state is cancelled via homing `$H` or unlocking `$X`. Only appears immediately after the `Grbl` welcome message when initialized with an alarm. Startup lines are not executed at initialization if this message is present and the alarm is active.
|
||||||
|
|
||||||
|
- `[MSG:Caution: Unlocked]` - Appears as an alarm unlock `$X` acknowledgement. An 'ok' still appears immediately after to denote the `$X` was parsed and executed. This message reminds the user that Grbl is operating under an unlock state, where startup lines have still not be executed and should be cautious and mindful of what they do. Grbl may not have retained machine position due to an alarm suddenly halting the machine. A reset or re-homing Grbl is highly recommended as soon as possible, where any startup lines will be properly executed.
|
||||||
|
|
||||||
|
- `[MSG:Enabled]` - Appears as a check-mode `$C` enabled acknowledgement. An 'ok' still appears immediately after to denote the `$C` was parsed and executed.
|
||||||
|
|
||||||
|
- `[MSG:Disabled]` - Appears as a check-mode `$C` disabled acknowledgement. An 'ok' still appears immediately after to denote the `$C` was parsed and executed. Grbl is automatically reset afterwards to restore all default g-code parser states changed by the check-mode.
|
||||||
|
|
||||||
|
- `[MSG:Check Door]` - This message appears whenever the safety door detected as open. This includes immediately upon a safety door switch detects a pin change or appearing after the welcome message, if the safety door is ajar when Grbl initializes after a power-up/reset.
|
||||||
|
|
||||||
|
- If in motion and the safety door switch is triggered, Grbl will immediately send this message, start a feed hold, and place Grbl into a suspend with the DOOR state.
|
||||||
|
- If not in motion and not at startup, the same process occurs without the feed hold.
|
||||||
|
- If Grbl is in a DOOR state and already suspended, any detected door switch pin detected will generate this message, including a door close.
|
||||||
|
- If this message appears at startup, Grbl will suspended into immediately into the DOOR state. The startup lines are executed immediately after the DOOR state is exited by closing the door and sending Grbl a resume command.
|
||||||
|
|
||||||
|
- `[MSG:Check Limits]` - If Grbl detects a limit switch as triggered after a power-up/reset and hard limits are enabled, this will appear as a courtesy message immediately after the Grbl welcome message.
|
||||||
|
|
||||||
|
- `[MSG:Pgm End]` - M2/30 program end message to denote g-code modes have been restored to defaults according to the M2/30 g-code description.
|
||||||
|
|
||||||
|
- `[MSG:Restoring defaults]` - Appears as an acknowledgement message when restoring EEPROM defaults via a `$RST=` command. An 'ok' still appears immediately after to denote the `$RST=` was parsed and executed.
|
||||||
|
|
||||||
|
- `[MSG:Sleeping]` - Appears as an acknowledgement message when Grbl's sleep mode is invoked by issuing a `$SLP` command when in IDLE or ALARM states. Note that Grbl-Mega may invoke this at any time when the sleep timer option has been enabled and the timeout has been exceeded. Grbl may only be exited by a reset in the sleep state and will automatically enter an alarm state since the steppers were disabled.
|
||||||
|
- NOTE: Sleep will also invoke the parking motion, if it's enabled. However, if sleep is commanded during an ALARM, Grbl will not park and will simply de-energize everything and go to sleep.
|
||||||
|
|
||||||
|
- **Queried Feedback Messages:**
|
||||||
|
|
||||||
|
- `[GC:]` G-code Parser State Message
|
||||||
|
- Initiated by the user via a `$G` command. Grbl replies as follows, where the `[GC:` denotes the message type and is followed by a separate `ok` to confirm the `$G` was executed.
|
||||||
|
```
|
||||||
|
[GC:G0 G54 G17 G21 G90 G94 M0 M5 M9 T0 F0. S0.]
|
||||||
|
ok
|
||||||
|
```
|
||||||
|
- The shown g-code are the current modal states of Grbl's g-code parser. This may not correlate to what is executing since there are usually several motions queued in the planner buffer.
|
||||||
|
|
||||||
|
- `[HLP:]` : Initiated by the user via a `$` print help command. The help message is shown below with a separate `ok` to confirm the `$` was executed.
|
||||||
|
```
|
||||||
|
[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $C $X $H ~ ! ? ctrl-x]
|
||||||
|
ok
|
||||||
|
```
|
||||||
|
- The `$#` print parameter data query produces a large set of data which shown below and completed by an `ok` response message.
|
||||||
|
|
||||||
|
- Each line of the printout is starts with the data type, a `:`, and followed by the data values. If there is more than one, the order is XYZ axes, separated by commas.
|
||||||
|
|
||||||
|
```
|
||||||
|
[G54:0.000,0.000,0.000]
|
||||||
|
[G55:0.000,0.000,0.000]
|
||||||
|
[G56:0.000,0.000,0.000]
|
||||||
|
[G57:0.000,0.000,0.000]
|
||||||
|
[G58:0.000,0.000,0.000]
|
||||||
|
[G59:0.000,0.000,0.000]
|
||||||
|
[G28:0.000,0.000,0.000]
|
||||||
|
[G30:0.000,0.000,0.000]
|
||||||
|
[G92:0.000,0.000,0.000]
|
||||||
|
[TLO:0.000]
|
||||||
|
[PRB:0.000,0.000,0.000:0]
|
||||||
|
ok
|
||||||
|
```
|
||||||
|
|
||||||
|
- The `PRB:` probe parameter message includes an additional `:` and suffix value is a boolean. It denotes whether the last probe cycle was successful or not.
|
||||||
|
|
||||||
|
- `[VER:]` : Indicates build info and string from a `$I` user query. The build info message is shown below with a separate `ok` to confirm the `$I` was executed.
|
||||||
|
```
|
||||||
|
[VER:v1.1a.20160923:]
|
||||||
|
ok
|
||||||
|
```
|
||||||
|
- A string may appear after the `:` colon. It is a stored EEPROM string a user or OEM can place there for personal use or tracking purposes.
|
||||||
|
|
||||||
|
- `[echo:]` : Indicates an automated line echo from a command just prior to being parsed and executed. May be enabled only by a config.h option. Often used for debugging communication issues. A typical line echo message is shown below. A separate `ok` will eventually appear to confirm the line has been parsed and executed, but may not be immediate as with any line command containing motions.
|
||||||
|
```
|
||||||
|
[echo:G1X0.540Y10.4F100]
|
||||||
|
```
|
||||||
|
- NOTE: The echoed line will have been pre-parsed a bit by Grbl. No spaces or comments will appear and all letters will be capitalized.
|
||||||
|
|
||||||
|
------
|
||||||
|
|
||||||
|
#### Startup Line Execution
|
||||||
|
|
||||||
|
- `>G54G20:ok` : The open chevron indicates a startup line has just executed. The startup line `G54G20` immediately follows the `>` character and is followed by an `:ok` response to indicate it executed successfully.
|
||||||
|
|
||||||
|
- A startup line will execute upon initialization only if a line is present and if Grbl is not in an alarm state.
|
||||||
|
|
||||||
|
- The `:ok` on the same line is intentional. It prevents this `ok` response from being counted as part of a stream, because it is not tied to a sent command, but an internally-generated one.
|
||||||
|
|
||||||
|
- There should always be an appended `:ok` because the startup line is checked for validity before it is stored in EEPROM. In the event that it's not, Grbl will print `>G54G20:error:X`, where `X` is the error code explaining why the startup line failed to execute.
|
||||||
|
|
||||||
|
- In the rare chance that there is an EEPROM read error, the startup line execution will print `>:error:7` with no startup line and a error code `7` for a read fail. Grbl will also automatically wipe and try to restore the problematic EEPROM.
|
||||||
|
|
||||||
|
|
||||||
|
------
|
||||||
|
|
||||||
|
#### Real-time Status reports
|
||||||
|
|
||||||
|
- Contains real-time data of Grbl’s state, position, and other data required independently of the stream.
|
||||||
|
|
||||||
|
- Categorized as a real-time message, where it is a separate message that should not be counted as part of the streaming protocol. It may appear at any given time.
|
||||||
|
|
||||||
|
- A status report is initiated by sending Grbl a '?' character.
|
||||||
|
|
||||||
|
- Like all real-time commands, the '?' character is intercepted and never enters the serial buffer. It's never a part of the stream and can be sent at any time.
|
||||||
|
|
||||||
|
- Grbl will generate and transmit a report within ~5-20 milliseconds.
|
||||||
|
|
||||||
|
- Every ’?’ command sent by a GUI is not guaranteed with a response. The following are the current scenarios when Grbl may not immediately or ignore a status report request. _NOTE: These may change in the future and will be documented here._
|
||||||
|
|
||||||
|
- If two or more '?' queries are sent before the first report is generated, the additional queries are ignored.
|
||||||
|
|
||||||
|
- A soft-reset commanded clears the last status report query.
|
||||||
|
|
||||||
|
- When Grbl throws a critical alarm from a limit violation. A soft-reset is required to resume operation.
|
||||||
|
|
||||||
|
- During a homing cycle.
|
||||||
|
|
||||||
|
- **Message Construction:**
|
||||||
|
|
||||||
|
- A message is a single line of ascii text, completed by a carriage return and line feed.
|
||||||
|
|
||||||
|
- `< >` Chevrons uniquely enclose reports to indicate message type.
|
||||||
|
|
||||||
|
- `|` Pipe delimiters separate data fields inside the report.
|
||||||
|
|
||||||
|
- The first data field is an exception to the following data field rules. See 'Machine State' description for details.
|
||||||
|
|
||||||
|
- All remaining data fields consist of a data type followed by a `:` colon delimiter and data values. `type:value(s)`
|
||||||
|
|
||||||
|
- Data values are given either as as one or more pre-defined character codes to indicate certain states/conditions or as numeric values, which are separated by a `,` comma delimiter when more than one is present. Numeric values are also in a pre-defined order and units of measure.
|
||||||
|
|
||||||
|
- The first (Machine State) and second (Current Position) data fields are always included in every report.
|
||||||
|
|
||||||
|
- Assume any following data field may or may not exist and can be in any order. The `$10` status report mask setting can alter what data is present and certain data fields can be reported intermittently (see descriptions for details.)
|
||||||
|
|
||||||
|
- The `$13` report inches settings alters the units of some data values. `$13=0` false indicates mm-mode, while `$13=1` true indicates inch-mode reporting. Keep note of this setting and which report values can be altered.
|
||||||
|
|
||||||
|
- **Data Field Descriptions:**
|
||||||
|
|
||||||
|
- **Machine State:**
|
||||||
|
|
||||||
|
- Valid states types: `Idle, Run, Hold, Jog, Alarm, Door, Check, Home, Sleep`
|
||||||
|
|
||||||
|
- Sub-states may be included via `:` a colon delimiter and numeric code.
|
||||||
|
|
||||||
|
- Current sub-states are:
|
||||||
|
|
||||||
|
- `Hold:0` Hold complete. Ready to resume.
|
||||||
|
|
||||||
|
- `Hold:1` Hold in-progress. Reset will throw an alarm.
|
||||||
|
|
||||||
|
- `Door:0` Door closed. Ready to resume.
|
||||||
|
|
||||||
|
- `Door:1` Machine stopped. Door still ajar. Can't resume until closed.
|
||||||
|
|
||||||
|
- `Door:2` Door opened. Hold (or parking retract) in-progress. Reset will throw an alarm.
|
||||||
|
|
||||||
|
- `Door:3` Door closed and resuming. Restoring from park, if applicable. Reset will throw an alarm.
|
||||||
|
|
||||||
|
- This data field is always present as the first field.
|
||||||
|
|
||||||
|
- **Current Position:**
|
||||||
|
|
||||||
|
- Depending on `$10` status report mask settings, position may be sent as either:
|
||||||
|
|
||||||
|
- `MPos:0.000,-10.000,5.000` machine position or
|
||||||
|
|
||||||
|
- `WPos:-2.500,0.000,11.000` work position
|
||||||
|
|
||||||
|
- Three position values are given in the order of X, Y, and Z. A fourth position value may exist in later versions for the A-axis.
|
||||||
|
|
||||||
|
- `$13` report inches user setting effects these values and is given as either mm or inches.
|
||||||
|
|
||||||
|
- This data field is always present as the second field.
|
||||||
|
|
||||||
|
- **Work Coordinate Offset:**
|
||||||
|
|
||||||
|
- `WCO:0.000,1.551,5.664` is the current work coordinate offset of the g-code parser, which is the sum of the current work coordinate system, G92 offsets, and G43.1 tool length offset.
|
||||||
|
|
||||||
|
- Machine position and work position are related by this simple equation per axis: `WPos = MPos - WCO`
|
||||||
|
|
||||||
|
- Values are given in the order of the X,Y, and Z axes offsets. A fourth offset value may exist in later versions for the A-axis.
|
||||||
|
- `$13` report inches user setting effects these values and is given as either mm or inches.
|
||||||
|
|
||||||
|
- `WCO:` values don't change often during a job once set and only requires intermittent refreshing.
|
||||||
|
|
||||||
|
- This data field appears:
|
||||||
|
|
||||||
|
- In every 10 or 30 (configurable 1-255) status reports, depending on if Grbl is in a motion state or not.
|
||||||
|
|
||||||
|
- Immediately in the next report, if an offset value has changed.
|
||||||
|
|
||||||
|
- In the first report after a reset/power-cycle.
|
||||||
|
|
||||||
|
- This data field will not appear if:
|
||||||
|
|
||||||
|
- It is disabled in the config.h file. No `$` mask setting available.
|
||||||
|
|
||||||
|
- The refresh counter is in-between intermittent reports.
|
||||||
|
|
||||||
|
- **Buffer State:**
|
||||||
|
|
||||||
|
- `Bf:15,128`. The first value is the number of available blocks in the planner buffer and the second is number of available bytes in the serial RX buffer.
|
||||||
|
|
||||||
|
- The usage of this data is generally for debugging an interface, but is known to be used to control some GUI-specific tasks. While this is disabled by default, GUIs should expect this data field to appear, but they may ignore it, if desired.
|
||||||
|
|
||||||
|
- NOTE: The buffer state values changed from showing "in-use" blocks or bytes to "available". This change does not require the GUI knowing how many block/bytes Grbl has been compiled with.
|
||||||
|
|
||||||
|
- This data field appears:
|
||||||
|
|
||||||
|
- In every status report when enabled. It is disabled in the settings mask by default.
|
||||||
|
|
||||||
|
- This data field will not appear if:
|
||||||
|
|
||||||
|
- It is disabled by the `$` status report mask setting or disabled in the config.h file.
|
||||||
|
|
||||||
|
- **Line Number:**
|
||||||
|
|
||||||
|
- `Ln:99999` indicates line 99999 is currently being executed. This differs from the `$G` line `N` value since the parser is usually queued few blocks behind execution.
|
||||||
|
|
||||||
|
- Compile-time option only because of memory requirements. However, if a GUI passes indicator line numbers onto Grbl, it's very useful to determine when Grbl is executing them.
|
||||||
|
|
||||||
|
- This data field will not appear if:
|
||||||
|
|
||||||
|
- It is disabled in the config.h file. No `$` mask setting available.
|
||||||
|
|
||||||
|
- The line number reporting not enabled in config.h. Different option to reporting data field.
|
||||||
|
|
||||||
|
- No line number or `N0` is passed with the g-code block.
|
||||||
|
|
||||||
|
- Grbl is homing, jogging, parking, or performing a system task/motion.
|
||||||
|
|
||||||
|
- There is no motion in the g-code block like a `G4P1` dwell. (May be fixed in later versions.)
|
||||||
|
|
||||||
|
- **Current Rate:**
|
||||||
|
|
||||||
|
- `F:1000.` indicates current actual feed rate (speed) of the executing motion. Depending on machine max rate settings and acceleration, this value may not be the programmed rate.
|
||||||
|
|
||||||
|
- Value units, either in mm/min or inches/min, is dependent on the `$` report inches user setting.
|
||||||
|
|
||||||
|
- As a operational note, reported rate is typically 30-50 msec behind actual position reported.
|
||||||
|
|
||||||
|
- This data field will not appear if:
|
||||||
|
|
||||||
|
- It is disabled in the config.h file. No `$` mask setting available.
|
||||||
|
|
||||||
|
- **Input Pin State:**
|
||||||
|
|
||||||
|
- `Pn:XYZPDHRS` indicates which input pins Grbl has detected as 'triggered'.
|
||||||
|
|
||||||
|
- Pin state is evaluated every time a status report is generated. All input pin inversions are appropriately applied to determine 'triggered' states.
|
||||||
|
|
||||||
|
- Each letter of `XYZPDHRS` denotes a particular 'triggered' input pin.
|
||||||
|
|
||||||
|
- `X Y Z` XYZ limit pins, respectively
|
||||||
|
|
||||||
|
- `P` the probe pin.
|
||||||
|
|
||||||
|
- `D H R S` the door, hold, soft-reset, and cycle-start pins, respectively.
|
||||||
|
|
||||||
|
- Example: `Pn:PZ` indicates the probe and z-limit pins are 'triggered'.
|
||||||
|
|
||||||
|
- Note: `A` may be added in later versions for an A-axis limit pin.
|
||||||
|
|
||||||
|
- Assume input pin letters are presented in no particular order.
|
||||||
|
|
||||||
|
- One or more 'triggered' pin letter(s) will always be present with a `Pn:` data field.
|
||||||
|
|
||||||
|
- This data field will not appear if:
|
||||||
|
|
||||||
|
- It is disabled in the config.h file. No `$` mask setting available.
|
||||||
|
|
||||||
|
- No input pins are detected as triggered.
|
||||||
|
|
||||||
|
- **Override Values:**
|
||||||
|
|
||||||
|
- `Ov:100,100,100` indicates current override values in percent of programmed values for feed, rapids, and spindle speed, respectively.
|
||||||
|
|
||||||
|
- Override values don't change often during a job once set and only requires intermittent refreshing. This data field appears:
|
||||||
|
|
||||||
|
- After 10 or 20 (configurable 1-255) status reports, depending on is in a motion state or not.
|
||||||
|
|
||||||
|
- If an override value has changed, this data field will appear immediately in the next report. However, if `WCO:` is present, this data field will be delayed one report.
|
||||||
|
|
||||||
|
- In the second report after a reset/power-cycle.
|
||||||
|
|
||||||
|
- This data field will not appear if:
|
||||||
|
|
||||||
|
- It is disabled in the config.h file. No `$` mask setting available.
|
||||||
|
|
||||||
|
- The override refresh counter is in-between intermittent reports.
|
||||||
|
|
||||||
|
- `WCO:` exists in current report during refresh. Automatically set to try again on next report.
|
||||||
|
|
||||||
|
- **Toggle Overrides:**
|
||||||
|
|
||||||
|
- `T:SFM` indicates a toggle override is in effect or has been commanded.
|
||||||
|
|
||||||
|
- Like the pin state field, each letter denotes a particular toggle override.
|
||||||
|
|
||||||
|
- `S` indicates the spindle stop toggle override is in effect. It will appear as long as the spindle stop override is active.
|
||||||
|
|
||||||
|
- `F` indicates the flood coolant toggle override was activated. It will only appear once after it has executed the coolant state change.
|
||||||
|
|
||||||
|
- `M` indicates the mist coolant toggle override was activated, if mist coolant is enabled via config.h. It will only appear once after it has executed the coolant state change.
|
||||||
|
|
||||||
|
- Assume toggle override letters are presented in no particular order.
|
||||||
|
|
||||||
|
- One or more active toggle override letter(s) will always be present with a `T:` data field.
|
||||||
|
|
||||||
|
- This data field appears:
|
||||||
|
|
||||||
|
- If a toggle override is active or has recently executed and only when the override values field is also present (see override value field rules).
|
||||||
|
|
||||||
|
- This data field will not appear if:
|
||||||
|
|
||||||
|
- If no toggle override is active or has been executed.
|
||||||
|
|
||||||
|
- It is disabled in the config.h file. No `$` mask setting available.
|
||||||
|
|
||||||
|
- If override refresh counter is in-between intermittent reports.
|
||||||
|
|
||||||
|
- `WCO:` exists in current report during refresh. Automatically set to try again on next report.
|
||||||
|
|
||||||
|
|
||||||
|
-------
|
||||||
|
# Message Summary
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
- `ok` / `error:x` : Normal send command and execution response acknowledgement. Used for streaming.
|
||||||
|
|
||||||
|
- `< >` : Enclosed chevrons contains status report data.
|
||||||
|
|
||||||
|
- `Grbl X.Xx ['$' for help]` : Welcome message indicates initialization.
|
||||||
|
|
||||||
|
- `ALARM:x` : Indicates an alarm has been thrown. Grbl is now in an alarm state.
|
||||||
|
|
||||||
|
- `$x=val` and `$Nx=line` indicate a settings printout from a `$` and `$N` user query, respectively.
|
||||||
|
|
||||||
|
- `[MSG:]` : Indicates a non-queried feedback message.
|
||||||
|
|
||||||
|
- `[GC:]` : Indicates a queried `$G` g-code state message.
|
||||||
|
|
||||||
|
- `[HLP:]` : Indicates the help message.
|
||||||
|
|
||||||
|
- `[G54:]`, `[G55:]`, `[G56:]`, `[G57:]`, `[G58:]`, `[G59:]`, `[G28:]`, `[G30:]`, `[G92:]`, `[TLO:]`, and `[PRB:]` messages indicate the parameter data printout from a `$#` user query.
|
||||||
|
|
||||||
|
- `[VER:]` : Indicates build info and string from a `$I` user query.
|
||||||
|
|
||||||
|
- `[echo:]` : Indicates an automated line echo from a pre-parsed string prior to g-code parsing. Enabled by config.h option.
|
||||||
|
|
||||||
|
- `>G54G20:ok` : The open chevron indicates startup line execution. The `:ok` suffix shows it executed correctly without adding an unmatched `ok` response on a new line.
|
||||||
|
|
||||||
|
On a final note, this interface tweak came about out of necessity, as more data is being sent back from Grbl and it is capable of doing many more things. 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.
|
90
doc/markdown/jogging.md
Normal file
90
doc/markdown/jogging.md
Normal file
@ -0,0 +1,90 @@
|
|||||||
|
# Grbl v1.1 Jogging
|
||||||
|
|
||||||
|
## How to Use
|
||||||
|
Executing a jog requires a specific command structure, as described below:
|
||||||
|
|
||||||
|
- The first three characters must be '$J=' to indicate the jog.
|
||||||
|
- The jog command follows immediate after the '=' and works like a normal G1 command.
|
||||||
|
- Feed rate is only interpreted in G94 units per minute. A prior G93 state is ignored during jog.
|
||||||
|
- Required words:
|
||||||
|
- XYZ: One or more axis words with target value.
|
||||||
|
- F - Feed rate value. NOTE: Each jog requires this value and is not treated as modal.
|
||||||
|
- 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.
|
||||||
|
- G20 or G21 - Inch and millimeter mode
|
||||||
|
- G90 or G91 - Absolute and incremental distances
|
||||||
|
- G53 - Move in machine coordinates
|
||||||
|
- All other g-codes, m-codes, and value words are not accepted in the jog command.
|
||||||
|
- Spaces and comments are allowed in the command. These are removed by the pre-parser.
|
||||||
|
|
||||||
|
- Example: G21 and G90 are active modal states prior to jogging. These are sequential commands.
|
||||||
|
- `$J=X10.0 Y-1.5` will move to X=10.0mm and Y=-1.5mm in work coordinate frame (WPos).
|
||||||
|
- `$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.
|
||||||
|
- `$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).
|
||||||
|
|
||||||
|
Jog commands behave almost identically to normal g-code streaming. Every jog command will
|
||||||
|
return an 'ok' when the jogging motion has been parsed and is setup for execution. If a
|
||||||
|
command is not valid, Grbl will return an 'error:'. Multiple jogging commands may be
|
||||||
|
queued in sequence.
|
||||||
|
|
||||||
|
The main differences are:
|
||||||
|
|
||||||
|
- During a jog, Grbl will report a 'Jog' state while executing the jog.
|
||||||
|
- A jog command will only be accepted when Grbl is in either the 'Idle' or 'Jog' states.
|
||||||
|
- Jogging motions may not be mixed with g-code commands while executing, which will return a lockout error, if attempted.
|
||||||
|
- 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.
|
||||||
|
- 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.
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
------
|
||||||
|
|
||||||
|
## Joystick Implementation
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
- Basic Implementation Overview:
|
||||||
|
- Create a loop to read the joystick signal and translate it to a desired jog motion vector.
|
||||||
|
- Send Grbl a very short `G91` incremental distance jog command with a feed rate based on the joystick throw.
|
||||||
|
- Wait for an 'ok' acknowledgement before restarting the loop.
|
||||||
|
- Continually read the joystick input and send Grbl short jog motions to keep Grbl's planner buffer full.
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
#### How to compute incremental distances
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
`s = v * dt` - Computes distance traveled for next jog command.
|
||||||
|
|
||||||
|
where:
|
||||||
|
|
||||||
|
- `s` - Incremental distance of jog command.
|
||||||
|
- `dt` - Estimated execution time of a single jog command in seconds.
|
||||||
|
- `v` - Current jog feed rate in **mm/sec**, not mm/min. Less than or equal to max jog rate.
|
||||||
|
- `N` - Number of Grbl planner blocks (`N=15`)
|
||||||
|
- `T = dt * N` - Computes total estimated latency in seconds.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
- `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.
|
||||||
|
|
||||||
|
- `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.
|
||||||
|
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
- 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.
|
||||||
|
|
||||||
|
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.
|
||||||
|
|
||||||
|
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!
|
||||||
|
|
||||||
|
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.
|
105
doc/markdown/old_wiki_pages/interface_notes.md
Normal file
105
doc/markdown/old_wiki_pages/interface_notes.md
Normal file
@ -0,0 +1,105 @@
|
|||||||
|
***
|
||||||
|
|
||||||
|
# Writing an Interface for Grbl
|
||||||
|
|
||||||
|
_**FOR DEVELOPERS ONLY: This section outlines the recommended ways to setup a communications and streaming protocol with Grbl for a GUI.**_
|
||||||
|
|
||||||
|
The general interface for Grbl has been described above, but what's missing is how to run an entire G-code program on Grbl, when it doesn't seem to have an upload feature. Or, how to build a decent GUI with real-time feedback. This is where this section fits in. Early on, users fiercely requested for flash drive, external RAM, LCD support, joysticks, or network support so they can upload a g-code program and run it directly on Grbl. The general answer to that is, good ideas, but Grbl doesn't need them. Grbl already has nearly all of the tools and features to reliably communicate with a simple graphical user interface (GUI). Plus, we want to minimize as much as we can on what Grbl should be doing, because, in the end, Grbl needs to be concentrating on producing clean, reliable motion. That's it.
|
||||||
|
|
||||||
|
|
||||||
|
## Streaming a G-Code Program to Grbl
|
||||||
|
|
||||||
|
Here we will describe three different streaming methods for Grbl GUIs, but really there's only two that we recommend using. One of the main problems with streaming to Grbl is the USB port itself. Arduinos and most all micro controllers use a USB-to-serial converter chip that, at times, behaves strangely and not typically how you'd expect, like USB packet buffering and delays that can wreak havoc to a streaming protocol. Another problem is how to deal with some of the latency and oddities of the PCs themselves, because none of them are truly real-time and always create micro-delays when executing other tasks. Regardless, we've come up with ways to ensure the G-code stream is reliable and simple.
|
||||||
|
|
||||||
|
#### Streaming Protocol: Simple Send-Response _[Recommended for Grbl v0.9+]_
|
||||||
|
The send-response streaming protocol is the most fool-proof and simplest method to stream a G-code program to Grbl. The host PC interface simply sends a line of G-code to Grbl and waits for an `ok` or `error:` response before sending the next line of G-code. So, no matter if Grbl needs to wait for room in the look-ahead planner buffer to finish parsing and executing the last line of G-code or if the the host computer is busy doing something, this guarantees both to the host PC and Grbl, the programmed G-code has been sent and received properly. An example of this protocol is published in our `simple_stream.py` script in our repository.
|
||||||
|
|
||||||
|
However, it's also the slowest of three outlined streaming protocols. Grbl essentially has two buffers between the execution of steps and the host PC interface. One of them is the serial receive buffer. This briefly stores up to 127 characters of data received from the host PC until Grbl has time to fetch and parse the line of G-code. The other buffer is the look-ahead planner buffer. This buffer stores up to 17 line motions that are acceleration-planned and optimized for step execution. Since the send-response protocol receives a line of G-code while the host PC waits for a response, Grbl's serial receive buffer is usually empty and under-utilized. If Grbl is actively running and executing steps, Grbl will immediately begin to execute and empty the look-ahead planner buffer, while it sends the response to the host PC, waits for the next line from the host PC, upon receiving it, parse and plan it, and add it to the end of the look-ahead buffer.
|
||||||
|
|
||||||
|
Although this communication lag may take only a fraction of a second, there is a cumulative effect, because there is a lag with every G-code block sent to Grbl. In certain scenarios, like a G-code program containing lots of sequential, very short, line segments with high feed rates, the cumulative lag can be large enough to empty and starve the look-ahead planner buffer within this time. This could lead to start-stop motion when the streaming can't keep up with G-code program execution. Also, since Grbl can only plan and optimize what's in the look-ahead planner buffer, the performance through these types of motions will never be full-speed, because look-ahead buffer will always be partially full when using this streaming method. If your expected application doesn't contain a lot of these short line segments with high feed rates, this streaming protocol should be more than adequate for a vast majority of applications, is very robust, and is a quick way to get started. However, we do not recommend using this method for Grbl versions v0.8 or prior due to some performance issues with these versions.
|
||||||
|
|
||||||
|
#### Streaming Protocol: Via Flow Control (XON/XOFF)
|
||||||
|
|
||||||
|
To avoid the risk of starving the look-ahead planner buffer, a flow control streaming protocol can be used to try to keep Grbl's serial receive buffer full, so that Grbl has immediate access to the next g-code line to parse and plan without having to wait for the host PC to send it. Flow control, also known as XON/XOFF software flow control, uses two special characters to tell the host PC when it has or doesn't have room in the serial receive buffer to receive more data. When there is room, usually at 20% full, the special character is sent to the host PC indicating ready-to-receive. The host PC will begin to send data until it receives the other stop-receive special character, usually at 80% full. Grbl's XON/XOFF software flow control feature may be enabled through the config.h, but is not officially supported for the following reasons.
|
||||||
|
|
||||||
|
While sound in logic, software flow control has a number of problems. The timing between Grbl and the host PC is almost never perfectly in sync, in large part due to the USB protocol and the USB-serial converter chips on every Arduino. This poses a big problem when sending and receiving these special flow-control characters. When Grbl's serial receive buffer is low, the time between when it sends the ready-to-receive character and when the host PC sends more data all depends everything in between. If the host PC is busy or the Arduino USB-serial converter is not sending the character on time, this lag can cause Grbl to wait for more serial data to come in before parsing and executing the next line of G-code. Even worse though, if the serial receive buffer is nearing full and the stop-receive character is sent, the host PC may not receive the signal in time to stop the data transfer and over-flow Grbl's serial buffer. This is bad and will corrupt the data stream.
|
||||||
|
|
||||||
|
Because the software flow-control method is dependent on the performance of the USB-serial converter on the Arduino and the host PC, the low and high watermarks for the ready-to-receive and stop-receive characters must be tuned for each case. Thus, it's not really a robust solution. In our experience with XON/XOFF software flow control, it absolutely **DOES NOT** work with Arduinos with the Atmega8U/16U USB-serial converter chips (on all current Arduinos from the Uno to Mega2560). For some reason, there are USB packet delays that are out of Grbl's control and almost always led to data corruption. However, XON/XOFF worked, but only on older Arduinos or micro controllers that featured an FTDI RS232 USB-serial converter chip, such as the Duemilanove or controllers with an FTDI break-out board. The FTDI's firmware reliably sent the XON/XOFF special characters in time and on time. We're not sure why there is such a difference between them.
|
||||||
|
|
||||||
|
If you decide to use XON/XOFF software flow control for your GUI, keep in mind that, at the moment, it'll only really works with FTDI USB-serial converters. But, the great thing about this method is that you can connect with Grbl over a serial emulator program like Coolterm, enable XON/XOFF flow control, cut-and-paste an entire g-code program into it, and Grbl will execute it completely. (Nice but not really necessary.)
|
||||||
|
|
||||||
|
#### Streaming Protocol: Character-Counting _[**Recommended with Reservations**]_
|
||||||
|
|
||||||
|
To get the best of both worlds, the simplicity and reliability of the send-response method and assurance of maximum performance with software flow control, we came up with a simple character-counting protocol for streaming a G-code program to Grbl. It works like the send-response method, where the host PC sends a line of G-code for Grbl to execute and waits for a response, but, rather than needing special XON/XOFF characters for flow control, this protocol simply uses Grbl's responses as a way to reliably track how much room there is in Grbl's serial receive buffer. An example of this protocol is outlined in the `stream.py` streaming script in our repo.
|
||||||
|
|
||||||
|
The main difference between this protocol and the others is the host PC needs to maintain a standing count of how many characters it has sent to Grbl and then subtract the number of characters corresponding to the line executed with each Grbl response. Suppose there is a short G-code program that has 5 lines with 25, 40, 31, 58, and 20 characters (counting the line feed and carriage return characters too). We know Grbl has a 127 character serial receive buffer, and the host PC can send up to 127 characters without overflowing the buffer. If we let the host PC send as many complete lines as we can without over flowing Grbl's serial receive buffer, the first three lines of 25, 40, and 31 characters can be sent for a total of 96 characters. When Grbl responds, we know the first line has been processed and is no longer in the serial read buffer. As it stands, the serial read buffer now has the 40 and 31 character lines in it for a total of 71 characters. The host PC needs to then determine if it's safe to send the next line without overflowing the buffer. With the next line at 58 characters and the serial buffer at 71 for a total of 129 characters, the host PC will need to wait until more room has cleared from the serial buffer. When the next Grbl response comes in, the second line has been processed and only the third 31 character line remains in the serial buffer. At this point, it's safe to send the remaining last two 58 and 20 character lines of the g-code program for a total of 109.
|
||||||
|
|
||||||
|
While seemingly complicated, this character-counting streaming protocol is extremely effective in practice. It always ensures Grbl's serial read buffer is filled, while never overflowing it. It maximizes Grbl's performance by keeping the look-ahead planner buffer full by better utilizing the bi-directional data flow of the serial port, and it's fairly simple to implement as our `stream.py` script illustrates. We have stress-tested this character-counting protocol to extremes and it has not yet failed. Seemingly, only the speed of the serial connection is the limit.
|
||||||
|
|
||||||
|
_UPDATE: Up until recently, we've recommended that Grbl GUIs use this streaming protocol. It is indeed very efficient and effective, but there are a couple of additional things interface writers should aware of. These are issues being worked on for the v1.0 release._
|
||||||
|
- _Since the GUI is preloading Grbl's serial RX buffer with commands, Grbl will continually execute all of the queued g-code in the RX serial buffer. The first problem is if there is an error at the beginning of the RX buffer, Grbl will continue to execute the remaining buffered g-code and the GUI won't be able to control what happens. The interim solution is to check all of the g-code via the $C check mode, so all errors are vetted prior to streaming._
|
||||||
|
- _When Grbl stores data to EEPROM, the AVR requires all interrupts to be disabled during this write process, including the serial RX ISR. This means that if a g-code or Grbl `$` command writes to EEPROM, the data sent during the write may be lost. This is usually rare and typically occurs when streaming a G10 command inappropriately inside a program. For robustness, GUIs should track and detect these EEPROM write commands and handle them appropriately by waiting for the queue to finish executing before sending more data. Note that the simple send-response protocol doesn't not suffer from this issue._
|
||||||
|
|
||||||
|
|
||||||
|
## Interacting with Grbl's Systems
|
||||||
|
|
||||||
|
Along with streaming a G-code program, there a few more things to consider when writing a GUI for Grbl, such as how to use status reporting, real-time control commands, dealing with EEPROM, and general message handling.
|
||||||
|
|
||||||
|
#### Status Reporting
|
||||||
|
When a `?` character is sent to Grbl (no additional line feed or carriage return character required), it will immediately respond with something like `<Idle,MPos:0.000,0.000,0.000,WPos:0.000,0.000,0.000>` to report its state and current position. The `?` is always picked-off and removed from the serial receive buffer whenever Grbl detects one. So, these can be sent at any time. Also, to make it a little easier for GUIs to pick up on status reports, they are always encased by `<>` chevrons.
|
||||||
|
|
||||||
|
Developers can use this data to provide an on-screen position digital-read-out (DRO) for the user and/or to show the user a 3D position in a virtual workspace. We recommend querying Grbl for a `?` real-time status report at no more than 5Hz. 10Hz may be possible, but at some point, there are diminishing returns and you are taxing Grbl's CPU more by asking it to generate and send a lot of position data.
|
||||||
|
|
||||||
|
Grbl's status report is fairly simply in organization. It always starts with a word describing the machine state like `IDLE` (descriptions of these are available elsewhere in the Wiki). The following data values are usually in the order listed below and separated by commas, but may not be in the exact order or printed at all. Report output depends on the user's `$10` status report mask setting.
|
||||||
|
|
||||||
|
* `MPos:0.000,0.000,0.000` : Machine position listed as `X,Y,Z` coordinates. Units (mm or inch) depends on `$13` Grbl unit reporting setting.
|
||||||
|
* `WPos:0.000,0.000,0.000` : Work position listed as `X,Y,Z` coordinates. Units (mm or inch) depends on `$13` Grbl unit reporting setting.
|
||||||
|
* `Buf:0` : Number of motions queued in Grbl's planner buffer.
|
||||||
|
* `RX:0` : Number of characters queued in Grbl's serial RX receive buffer.
|
||||||
|
|
||||||
|
#### Real-Time Control Commands
|
||||||
|
The real-time control commands, `~` cycle start/resume, `!` feed hold, and `^X` soft-reset, all immediately signal Grbl to change its running state. Just like `?` status reports, these control characters are picked-off and removed from the serial buffer when they are detected and do not require an additional line-feed or carriage-return character to operate.
|
||||||
|
|
||||||
|
#### EEPROM Issues
|
||||||
|
EEPROM access on the Arduino AVR CPUs turns off all of the interrupts while the CPU reads and writes to EEPROM. This poses a problem for certain features in Grbl, particularly if a user is streaming and running a g-code program, since it can pause the main step generator interrupt from executing on time. Most of the EEPROM access is restricted by Grbl when it's in certain states, but there are some things that developers need to know.
|
||||||
|
|
||||||
|
* Settings can't be streamed to Grbl with either the XON/XOFF software flow control or the character-counting streaming protocols. Only the simple send-response protocol works. This is because during the EEPROM write, the AVR CPU also shuts-down the serial RX interrupt, which means data can get corrupted or lost. Note that the send-response protocol doesn't send any data until a response comes back.
|
||||||
|
|
||||||
|
* When changing work coordinates, printing `$#` parameters, or accessing the `G28`/`G30` predefined positions, Grbl has to fetch them from EEPROM. There is a small chance this access can pause the stepper or serial receive interrupt long enough to cause motion issues, but since it only fetches 12 bytes at a time at 2 cycles per fetch, the chances are very small that this will do anything to how Grbl runs. We just suggest keeping an eye on this and report to us any issues you might think are related to this.
|
||||||
|
|
||||||
|
For reference:
|
||||||
|
* Grbl's EEPROM write commands: `G10 L2`, `G10 L20`, `G28.1`, `G30.1`, `$x=`, `$I=`, `$Nx=`, `$RST=`
|
||||||
|
* Grbl's EEPROM read commands: `G54-G59`, `G28`, `G30`, `$$`, `$I`, `$N`, `$#`
|
||||||
|
|
||||||
|
#### Message Handling
|
||||||
|
Most of the feedback from Grbl fits into nice categories so GUIs can easily tell what is what. Here's how they are organized:
|
||||||
|
|
||||||
|
* `ok`: Standard all-is-good response to a single line sent to Grbl.
|
||||||
|
* `error:`: Standard error response to a single line sent to Grbl.
|
||||||
|
* `ALARM:`: A critical error message that occurred. All processes stopped until user acknowledgment.
|
||||||
|
* `[]`: All feedback messages are sent in brackets. These include parameter and g-code parser state print-outs.
|
||||||
|
* `<>`: Status reports are sent in chevrons.
|
||||||
|
|
||||||
|
There are few things that don't fit neatly into this setup at the moment. In the next version, we'll try to make this more universal, but for now, your GUIs will need to manually account for these:
|
||||||
|
* The startup message.
|
||||||
|
* `$` Help print-out.
|
||||||
|
* `$N` Start-up blocks execution after the startup message.
|
||||||
|
* The `$$` view Grbl settings print-out.
|
||||||
|
|
||||||
|
#### G-code Error Handling
|
||||||
|
|
||||||
|
As of Grbl v0.9, the g-code parser is fully standards-compilant with complete error-checking. When a G-code parser detects an error in a G-code block/line, the parser will dump everything in the block from memory and report an `error:` back to the user or GUI. This dump can pose problematic, because the bad G-code block may have contained some valuable positioning commands or feed rate settings.
|
||||||
|
|
||||||
|
It's highly recommended to do what all professional CNC controllers do when they detect an error in the G-code program, _**halt**_. Don't do anything further until the user has modified the G-code and fixed the error in their program. Otherwise, bad things could happen.
|
||||||
|
|
||||||
|
As a service to GUIs, Grbl has a "check G-code" mode, enabled by the `$C` system command. GUIs can stream a G-code program to Grbl, where it will parse it, error-check it, and report `ok`'s and `errors:`'s without powering on anything or moving. So GUIs can pre-check the programs before streaming them for real. To disable the "check G-code" mode, send another `$C` system command and Grbl will automatically soft-reset to flush and re-initialize the G-code parser and the rest of the system. This perhaps should be run in the background when a user first loads a program, before a user sets up his machine. This flushing and re-initialization clears `G92`'s by G-code standard, which some users still incorrectly use to set their part zero.
|
||||||
|
|
||||||
|
#### Jogging
|
||||||
|
|
||||||
|
Unfortunately, Grbl doesn't have a proper jogging interface, at least for now. This was to conserve precious flash space for the development of Grbl v0.9, but may be installed in the next release of Grbl. However, authors of Grbl GUIs have come up with ways to simulate jogging with Grbl by sending incremental motions, such as `G91 X0.1`, with each jogging click or key press. This works pretty well, but, if uncontrolled, a user can easily queue up more motions than they want without realizing it and move well-past their desired location.
|
||||||
|
|
||||||
|
The general methodology that has been shown to work is to simply restrict the number of jogging commands sent to Grbl. This can be done by disabling key repeating when held down. The planner buffer queue size can be tracked such that only a handful of motions can be queued and executed.
|
||||||
|
|
||||||
|
#### Synchronization
|
||||||
|
|
||||||
|
For situations when a GUI needs to run a special set of commands for tool changes, auto-leveling, etc, there often needs to be a way to know when Grbl has completed a task and the planner buffer is empty. The absolute simplest way to do this is to insert a `G4 P0.01` dwell command, where P is in seconds and must be greater than 0.0. This acts as a quick force-synchronization and ensures the planner buffer is completely empty before the GUI sends the next task to execute.
|
149
doc/markdown/realtime_cmds.md
Normal file
149
doc/markdown/realtime_cmds.md
Normal file
@ -0,0 +1,149 @@
|
|||||||
|
## Grbl v1.1 Realtime commands
|
||||||
|
|
||||||
|
Realtime commands are single control characters that may be sent to Grbl to command and perform an action in real-time. This means that they can be sent at anytime, anywhere, and Grbl will immediately respond, regardless of what it is doing at the time. These commands include a reset, feed hold, resume, status report query, and overrides (in v1.1).
|
||||||
|
|
||||||
|
A realtime command:
|
||||||
|
|
||||||
|
- Will execute within tens of milliseconds.
|
||||||
|
|
||||||
|
- Is a single character that may be sent to Grbl at any time.
|
||||||
|
|
||||||
|
- Does not require a line feed or carriage return after them.
|
||||||
|
|
||||||
|
- Is not considered a part of the streaming protocol.
|
||||||
|
|
||||||
|
- Are intercepted when they are received and never placed in a buffer to be parsed by Grbl.
|
||||||
|
|
||||||
|
- Will ignore multiple commands until it has executed the first received command.
|
||||||
|
|
||||||
|
- May be tied to an input pin and may be operated with a button or switch.
|
||||||
|
|
||||||
|
- Actions depends on state or what Grbl is doing. It may not do anything.
|
||||||
|
|
||||||
|
- Descriptions explain how they work and what to expect.
|
||||||
|
|
||||||
|
#### ASCII Realtime Command Descriptions
|
||||||
|
Four realtime commands are type-able by users on a keyboard and shown in the `$` Grbl help message. These realtime command characters control some of Grbl's basic functions.
|
||||||
|
|
||||||
|
- `0x18` (ctrl-x) : Soft-Reset
|
||||||
|
|
||||||
|
- Immediately halts and safely resets Grbl without a power-cycle.
|
||||||
|
- Accepts and executes this command at any time.
|
||||||
|
- If reset while in motion, Grbl will throw an alarm to indicate position may be lost from the motion halt.
|
||||||
|
- If reset while in not motion, position is retained and re-homing is not required.
|
||||||
|
- An input pin is available to connect a button or switch.
|
||||||
|
|
||||||
|
|
||||||
|
- `?` : Status Report Query
|
||||||
|
|
||||||
|
- Immediately generates and sends back runtime data with a status report.
|
||||||
|
- Accepts and executes this command at any time, except during a homing cycle and when critical alarm (hard/soft limit error) is thrown.
|
||||||
|
|
||||||
|
|
||||||
|
- `~` : Cycle Start / Resume
|
||||||
|
|
||||||
|
- Resumes a feed hold, a safety door/parking state when the door is closed, and the M0 program pause states.
|
||||||
|
- Command is otherwise ignored.
|
||||||
|
- If the parking compile-time option is enabled and the safety door state is ready to resume, Grbl will re-enable the spindle and coolant, move back into position, and then resume.
|
||||||
|
- An input pin is available to connect a button or switch.
|
||||||
|
|
||||||
|
|
||||||
|
- `!` : Feed Hold
|
||||||
|
|
||||||
|
- Places Grbl into a suspend or HOLD state. If in motion, the machine will decelerate to a stop and then be suspended.
|
||||||
|
- Command executes when Grbl is in an IDLE, RUN, or JOG state. It is otherwise ignored.
|
||||||
|
- If jogging, a feed hold will cancel the jog motion and flush all remaining jog motions in the planner buffer. The state will return from JOG to IDLE or DOOR, if was detected as ajar during the active hold.
|
||||||
|
- By machine control definition, a feed hold does not disable the spindle or coolant. Only motion.
|
||||||
|
- An input pin is available to connect a button or switch.
|
||||||
|
|
||||||
|
|
||||||
|
#### Extended-ASCII Realtime Command Descriptions
|
||||||
|
|
||||||
|
Grbl v1.1 installed more than a dozen new realtime commands to control feed, rapid, and spindle overrides. To help prevent users from inadvertently altering overrides with a keystroke and allow for more commands later on, all of the new control characters have been moved to the extended ASCII character set. These are not easily type-able on a keyboard, but, depending on the OS, they may be entered using specific keystroke and code. GUI developers will need to be able to send extended ASCII characters, values `128 (0x80)` to `255 (0xFF)`, to Grbl to take advantage of these new features.
|
||||||
|
|
||||||
|
- `0x84` : Safety Door
|
||||||
|
|
||||||
|
- Although typically connected to an input pin to detect the opening of a safety door, this command allows a GUI to enact the safety door behavior with this command.
|
||||||
|
- Immediately suspends into a DOOR state and disables the spindle and coolant. If in motion, the machine will decelerate to a stop and then be suspended.
|
||||||
|
- If executed during homing, Grbl will instead halt motion and throw a homing alarm.
|
||||||
|
- If already in a suspend state or HOLD, the DOOR state supersedes it.
|
||||||
|
- If the parking compile-time option is enabled, Grbl will park the spindle to a specified location.
|
||||||
|
- Command executes when Grbl is in an IDLE, HOLD, RUN, HOMING, or JOG state. It is otherwise ignored.
|
||||||
|
- If jogging, a safety door will cancel the jog and all queued motions in the planner buffer. When the safety door is closed and resumed, Grbl will return to an IDLE state.
|
||||||
|
- An input pin is available to connect a button or switch, if enabled with a compile-time option.
|
||||||
|
- Some builds of Grbl v0.9 used the `@` character for this command, but it was undocumented. Moved to extended-ASCII to prevent accidental commanding.
|
||||||
|
|
||||||
|
|
||||||
|
- `0x85` : Jog Cancel
|
||||||
|
|
||||||
|
- Immediately cancels the current jog state by a feed hold and automatically flushing any remaining jog commands in the buffer.
|
||||||
|
- Command is ignored, if not in a JOG state or if jog cancel is already invoked and in-process.
|
||||||
|
- Grbl will return to the IDLE state or the DOOR state, if the safety door was detected as ajar during the cancel.
|
||||||
|
|
||||||
|
|
||||||
|
- Feed Overrides
|
||||||
|
|
||||||
|
- Immediately alters the feed override value. An active feed motion is altered within tens of milliseconds.
|
||||||
|
- Does not alter rapid rates, which include G0, G28, and G30, or jog motions.
|
||||||
|
- Feed override value can not be 1% or greater than 200%
|
||||||
|
- If feed override value does not change, the command is ignored.
|
||||||
|
- Feed override range and increments may be changed in config.h.
|
||||||
|
- The commands are:
|
||||||
|
- `0x90` : Set 100% of programmed rate.
|
||||||
|
- `0x91` : Increase 10%
|
||||||
|
- `0x92` : Decrease 10%
|
||||||
|
- `0x93` : Increase 1%
|
||||||
|
- `0x94` : Decrease 1%
|
||||||
|
|
||||||
|
|
||||||
|
- Rapid Overrides
|
||||||
|
|
||||||
|
- Immediately alters the rapid override value. An active rapid motion is altered within tens of milliseconds.
|
||||||
|
- Only effects rapid motions, which include G0, G28, and G30.
|
||||||
|
- If rapid override value does not change, the command is ignored.
|
||||||
|
- Rapid override set values may be changed in config.h.
|
||||||
|
- The commands are:
|
||||||
|
- `0x95` : Set to 100% full rapid rate.
|
||||||
|
- `0x96` : Set to 50% of rapid rate.
|
||||||
|
- `0x97` : Set to 25% of rapid rate.
|
||||||
|
|
||||||
|
|
||||||
|
- Spindle Speed Overrides
|
||||||
|
|
||||||
|
- Immediately alters the spindle speed override value. An active spindle speed is altered within tens of milliseconds.
|
||||||
|
- Override values may be changed at any time, regardless of if the spindle is enabled or disabled.
|
||||||
|
- Spindle override value can not be 50% or greater than 200%
|
||||||
|
- If spindle override value does not change, the command is ignored.
|
||||||
|
- Spindle override range and increments may be altered in config.h.
|
||||||
|
- The commands are:
|
||||||
|
- `0x99` : Set 100% of programmed spindle speed
|
||||||
|
- `0x9A` : Increase 10%
|
||||||
|
- `0x9B` : Decrease 10%
|
||||||
|
- `0x9C` : Increase 1%
|
||||||
|
- `0x9D` : Decrease 1%
|
||||||
|
|
||||||
|
|
||||||
|
- `0x9E` : Toggle Spindle Stop
|
||||||
|
|
||||||
|
- Toggles spindle enable or disable state immediately, but only while in the HOLD state.
|
||||||
|
- The command is otherwise ignored, especially while in motion. This prevents accidental disabling during a job that can either destroy the part/machine or cause personal injury. Industrial machines handle the spindle stop override similarly.
|
||||||
|
- When motion restarts via cycle start, the last spindle state will be restored and wait 4.0 seconds (configurable) before resuming the tool path. This ensures the user doesn't forget to turn it back on.
|
||||||
|
- While disabled, spindle speed override values may still be altered and will be in effect once the spindle is re-enabled.
|
||||||
|
- If a safety door is opened, the DOOR state will supersede the spindle stop override, where it will manage the spindle re-energizing itself upon closing the door and resuming. The prior spindle stop override state is cleared and reset.
|
||||||
|
|
||||||
|
|
||||||
|
- `0xA0` : Toggle Flood Coolant
|
||||||
|
|
||||||
|
- Toggles flood coolant state and output pin until the next toggle or g-code command alters it.
|
||||||
|
- May be commanded at any time while in IDLE, RUN, or HOLD states. It is otherwise ignored.
|
||||||
|
- This override directly changes the coolant modal state in the g-code parser. Grbl will continue to operate normally like it received and executed an `M8` or `M9` g-code command.
|
||||||
|
- When `$G` g-code parser state is queried, the toggle override change will be reflected by an `M8` enabled or disabled with an `M9` or not appearing when `M7` is present.
|
||||||
|
|
||||||
|
|
||||||
|
- `0xA1` : Toggle Mist Coolant
|
||||||
|
|
||||||
|
- Enabled by `ENABLE_M7` compile-time option. Default is disabled.
|
||||||
|
- Toggles mist coolant state and output pin until the next toggle or g-code command alters it.
|
||||||
|
- May be commanded at any time while in IDLE, RUN, or HOLD states. It is otherwise ignored.
|
||||||
|
- This override directly changes the coolant modal state in the g-code parser. Grbl will continue to operate normally like it received and executed an `M7` or `M9` g-code command.
|
||||||
|
- When `$G` g-code parser state is queried, the toggle override change will be reflected by an `M7` enabled or disabled with an `M9` or not appearing when `M8` is present.
|
437
doc/markdown/settings.md
Normal file
437
doc/markdown/settings.md
Normal file
@ -0,0 +1,437 @@
|
|||||||
|
#### _Quick-Links:_
|
||||||
|
* [Getting Started](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9#getting-started)
|
||||||
|
* [Grbl Settings](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9#grbl-settings)
|
||||||
|
* [Grbl's Settings and What They Mean](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9#grbls-xval-settings-and-what-they-mean)
|
||||||
|
* [Grbl's Other `$` Commands](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9#grbls-other--commands)
|
||||||
|
* [Real-Time Commands](https://github.com/grbl/grbl/wiki/Configuring-Grbl-v0.9#real-time-commands----and-ctrl-x)
|
||||||
|
|
||||||
|
***
|
||||||
|
|
||||||
|
## Getting Started
|
||||||
|
|
||||||
|
First, connect to Grbl using the serial terminal of your choice.
|
||||||
|
|
||||||
|
Set the baud rate to **115200** as 8-N-1 (8-bits, no parity, and 1-stop bit.)
|
||||||
|
|
||||||
|
Once connected
|
||||||
|
you should get the Grbl-prompt, which looks like this:
|
||||||
|
|
||||||
|
```
|
||||||
|
Grbl 1.1c ['$' for help]
|
||||||
|
```
|
||||||
|
|
||||||
|
Type $ and press enter to have Grbl print a help message. You should not see any local echo of the $ and enter. Grbl should respond with:
|
||||||
|
|
||||||
|
```
|
||||||
|
[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H ~ ! ? ctrl-x]
|
||||||
|
```
|
||||||
|
|
||||||
|
The ‘$’-commands are Grbl system commands used to tweak the settings, view or change Grbl's states and running modes, and start a homing cycle. The last four **non**-'$' commands are realtime control commands that can be sent at anytime, no matter what Grbl is doing. These either immediately change Grbl's running behavior or immediately print a report of the important realtime data like current position (aka DRO).
|
||||||
|
|
||||||
|
***
|
||||||
|
|
||||||
|
##Grbl Settings
|
||||||
|
|
||||||
|
#### $$ - View Grbl settings
|
||||||
|
To view the settings, type `$$` and press enter after connecting to Grbl. Grbl should respond with a list of the current system settings, as shown in the example below. All of these settings are persistent and kept in EEPROM, so if you power down, these will be loaded back up the next time you power up your Arduino.
|
||||||
|
|
||||||
|
The `x` of `$x=val` indicates a particular setting, while `val` is the setting value. In prior versions of Grbl, each setting had a description next to it in `()` parentheses, but Grbl v1.1+ no longer includes them unfortunately. This was done to free up precious flash memory to add the new features available in v1.1. However, most good GUIs will help out by attaching descriptions for you, so you know what you are looking at.
|
||||||
|
|
||||||
|
```
|
||||||
|
$0=10
|
||||||
|
$1=25
|
||||||
|
$2=0
|
||||||
|
$3=0
|
||||||
|
$4=0
|
||||||
|
$5=0
|
||||||
|
$6=0
|
||||||
|
$10=1
|
||||||
|
$11=0.010
|
||||||
|
$12=0.002
|
||||||
|
$13=0
|
||||||
|
$20=0
|
||||||
|
$21=0
|
||||||
|
$22=1
|
||||||
|
$23=0
|
||||||
|
$24=25.000
|
||||||
|
$25=500.000
|
||||||
|
$26=250
|
||||||
|
$27=1.000
|
||||||
|
$30=1000.
|
||||||
|
$31=0.
|
||||||
|
$32=0
|
||||||
|
$100=250.000
|
||||||
|
$101=250.000
|
||||||
|
$102=250.000
|
||||||
|
$110=500.000
|
||||||
|
$111=500.000
|
||||||
|
$112=500.000
|
||||||
|
$120=10.000
|
||||||
|
$121=10.000
|
||||||
|
$122=10.000
|
||||||
|
$130=200.000
|
||||||
|
$131=200.000
|
||||||
|
$132=200.000
|
||||||
|
```
|
||||||
|
|
||||||
|
#### $x=val - Save Grbl setting
|
||||||
|
|
||||||
|
The `$x=val` command saves or alters a Grbl setting, which can be done manually by sending this command when connected to Grbl through a serial terminal program, but most Grbl GUIs will do this for you as a user-friendly feature.
|
||||||
|
|
||||||
|
To manually change e.g. the microseconds step pulse option to 10us you would type this, followed by an enter:
|
||||||
|
```
|
||||||
|
$0=10
|
||||||
|
```
|
||||||
|
If everything went well, Grbl will respond with an 'ok' and this setting is stored in EEPROM and will be retained forever or until you change them. You can check if Grbl has received and stored your setting correctly by typing `$$` to view the system settings again.
|
||||||
|
|
||||||
|
|
||||||
|
***
|
||||||
|
|
||||||
|
## Grbl's `$x=val` settings and what they mean
|
||||||
|
|
||||||
|
**NOTE: From Grbl v0.9 to Grbl v1.1, only `$10` status reports changed and new `$30`/ `$31` spindle rpm max/min and `$32` laser mode settings were added. Everything else is the same.**
|
||||||
|
|
||||||
|
#### $0 – Step pulse, microseconds
|
||||||
|
|
||||||
|
Stepper drivers are rated for a certain minimum step pulse length. Check the data sheet or just try some numbers. You want the shortest pulses the stepper drivers can reliably recognize. If the pulses are too long, you might run into trouble when running the system at very high feed and pulse rates, because the step pulses can begin to overlap each other. We recommend something around 10 microseconds, which is the default value.
|
||||||
|
|
||||||
|
#### $1 - Step idle delay, milliseconds
|
||||||
|
|
||||||
|
Every time your steppers complete a motion and come to a stop, Grbl will delay disabling the steppers by this value. **OR**, you can always keep your axes enabled (powered so as to hold position) by setting this value to the maximum 255 milliseconds. Again, just to repeat, you can keep all axes always enabled by setting `$1=255`.
|
||||||
|
|
||||||
|
The stepper idle lock time is the time length Grbl will keep the steppers locked before disabling. Depending on the system, you can set this to zero and disable it. On others, you may need 25-50 milliseconds to make sure your axes come to a complete stop before disabling. This is to help account for machine motors that do not like to be left on for long periods of time without doing something. Also, keep in mind that some stepper drivers don't remember which micro step they stopped on, so when you re-enable, you may witness some 'lost' steps due to this. In this case, just keep your steppers enabled via `$1=255`.
|
||||||
|
|
||||||
|
#### $2 – Step port invert, mask
|
||||||
|
|
||||||
|
This setting inverts the step pulse signal. By default, a step signal starts at normal-low and goes high upon a step pulse event. After a step pulse time set by `$0`, the pin resets to low, until the next step pulse event. When inverted, the step pulse behavior switches from normal-high, to low during the pulse, and back to high. Most users will not need to use this setting, but this can be useful for certain CNC-stepper drivers that have peculiar requirements. For example, an artificial delay between the direction pin and step pulse can be created by inverting the step pin.
|
||||||
|
|
||||||
|
This invert mask setting is a value which stores the axes to invert as bit flags. You really don't need to completely understand how it works. You simply need to enter the settings value for the axes you want to invert. For example, if you want to invert the X and Z axes, you'd send `$2=5` to Grbl and the setting should now read `$2=5 (step port invert mask:00000101)`.
|
||||||
|
|
||||||
|
| Setting Value | Mask |Invert X | Invert Y | Invert Z |
|
||||||
|
|:-------------:|:----:|:-------:|:--------:|:--------:|
|
||||||
|
| 0 | 00000000 |N | N | N |
|
||||||
|
| 1 | 00000001 |Y | N | N |
|
||||||
|
| 2 | 00000010 |N | Y | N |
|
||||||
|
| 3 | 00000011 |Y | Y | N |
|
||||||
|
| 4 | 00000100 |N | N | Y |
|
||||||
|
| 5 | 00000101 |Y | N | Y |
|
||||||
|
| 6 | 00000110 |N | Y | Y |
|
||||||
|
| 7 | 00000111 |Y | Y | Y |
|
||||||
|
|
||||||
|
#### $3 – Direction port invert, mask
|
||||||
|
|
||||||
|
This setting inverts the direction signal for each axis. By default, Grbl assumes that the axes move in a positive direction when the direction pin signal is low, and a negative direction when the pin is high. Often, axes don't move this way with some machines. This setting will invert the direction pin signal for those axes that move the opposite way.
|
||||||
|
|
||||||
|
This invert mask setting works exactly like the step port invert mask and stores which axes to invert as bit flags. To configure this setting, you simply need to send the value for the axes you want to invert. Use the table above. For example, if want to invert the Y axis direction only, you'd send `$3=2` to Grbl and the setting should now read `$3=2 (dir port invert mask:00000010)`
|
||||||
|
|
||||||
|
#### $4 - Step enable invert, boolean
|
||||||
|
|
||||||
|
By default, the stepper enable pin is high to disable and low to enable. If your setup needs the opposite, just invert the stepper enable pin by typing `$4=1`. Disable with `$4=0`. (May need a power cycle to load the change.)
|
||||||
|
|
||||||
|
#### $5 - Limit pins invert, boolean
|
||||||
|
|
||||||
|
By default, the limit pins are held normally-high with the Arduino's internal pull-up resistor. When a limit pin is low, Grbl interprets this as triggered. For the opposite behavior, just invert the limit pins by typing `$5=1`. Disable with `$5=0`. You may need a power cycle to load the change.
|
||||||
|
|
||||||
|
NOTE: If you invert your limit pins, you will need an external pull-down resistor wired in to all of the limit pins to prevent overloading the pins with current and frying them.
|
||||||
|
|
||||||
|
#### $6 - Probe pin invert, boolean
|
||||||
|
|
||||||
|
By default, the probe pin is held normally-high with the Arduino's internal pull-up resistor. When the probe pin is low, Grbl interprets this as triggered. For the opposite behavior, just invert the probe pin by typing `$6=1`. Disable with `$6=0`. You may need a power cycle to load the change.
|
||||||
|
|
||||||
|
NOTE: If you invert your probe pin, you will need an external pull-down resistor wired in to the probe pin to prevent overloading it with current and frying it.
|
||||||
|
|
||||||
|
|
||||||
|
#### $10 - Status report, mask
|
||||||
|
|
||||||
|
This setting determines what Grbl real-time data it reports back to the user when a '?' status report is sent. This data includes current run state, real-time position, real-time feed rate, pin states, current override values, buffer states, and the g-code line number currently executing (if enabled through compile-time options).
|
||||||
|
|
||||||
|
By default, the new report implementation in Grbl v1.1+ will include just about everything in the standard status report. A lot of the data is hidden and will appear only if it changes. This increases efficiency dramatically over of the old report style and allows you to get faster updates and still get more data about your machine. The interface documentation outlines how it works and most of it applies only to GUI developers or the curious.
|
||||||
|
|
||||||
|
To keep things simple and consistent, Grbl v1.1 has only two reporting options. These are primarily here just for users and developers to help set things up.
|
||||||
|
|
||||||
|
- Position type may be specified to show either machine position (`MPos:`) or work position (`WPos:`), but no longer both at the same time. Enabling work position is useful in certain scenarios when Grbl is being directly interacted with through a serial terminal, but _machine position reporting should be used by default._
|
||||||
|
- Usage data of Grbl's planner and serial RX buffers may be enabled. This shows the number of blocks or bytes available in the respective buffers. This is generally used to helps determine how Grbl is performing when testing out a streaming interface. _This should be disabled by default._
|
||||||
|
|
||||||
|
Use the table below enables and disable reporting options. Simply add the values listed of what you'd like to enable, then save it by sending Grbl your setting value. For example, the default report with machine position and no buffer data reports setting is `$10=1`. If work position and buffer data are desired, the setting will be `$10=2`.
|
||||||
|
|
||||||
|
| Report Type | Value | Description |
|
||||||
|
|:-------------:|:----:|:----:|
|
||||||
|
| Position Type | 1 | Enabled `MPos:`. Disabled `WPos:`. |
|
||||||
|
| Buffer Data | 2 | Enabled `Buf:` field appears with planner and serial RX available buffer.
|
||||||
|
|
||||||
|
#### $11 - Junction deviation, mm
|
||||||
|
|
||||||
|
Junction deviation is used by the acceleration manager to determine how fast it can move through line segment junctions of a G-code program path. For example, if the G-code path has a sharp 10 degree turn coming up and the machine is moving at full speed, this setting helps determine how much the machine needs to slow down to safely go through the corner without losing steps.
|
||||||
|
|
||||||
|
How we calculate it is a bit complicated, but, in general, higher values gives faster motion through corners, while increasing the risk of losing steps and positioning. Lower values makes the acceleration manager more careful and will lead to careful and slower cornering. So if you run into problems where your machine tries to take a corner too fast, *decrease* this value to make it slow down when entering corners. If you want your machine to move faster through junctions, *increase* this value to speed it up. For curious people, hit this [link](http://t.co/KQ5BvueY) to read about Grbl's cornering algorithm, which accounts for both velocity and junction angle with a very simple, efficient, and robust method.
|
||||||
|
|
||||||
|
#### $12 – Arc tolerance, mm
|
||||||
|
|
||||||
|
Grbl renders G2/G3 circles, arcs, and helices by subdividing them into teeny tiny lines, such that the arc tracing accuracy is never below this value. You will probably never need to adjust this setting, since `0.002mm` is well below the accuracy of most all CNC machines. But if you find that your circles are too crude or arc tracing is performing slowly, adjust this setting. Lower values give higher precision but may lead to performance issues by overloading Grbl with too many tiny lines. Alternately, higher values traces to a lower precision, but can speed up arc performance since Grbl has fewer lines to deal with.
|
||||||
|
|
||||||
|
For the curious, arc tolerance is defined as the maximum perpendicular distance from a line segment with its end points lying on the arc, aka a chord. With some basic geometry, we solve for the length of the line segments to trace the arc that satisfies this setting. Modeling arcs in this way is great, because the arc line segments automatically adjust and scale with length to ensure optimum arc tracing performance, while never losing accuracy.
|
||||||
|
|
||||||
|
#### $13 - Report inches, boolean
|
||||||
|
|
||||||
|
Grbl has a real-time positioning reporting feature to provide a user feedback on where the machine is exactly at that time, as well as, parameters for coordinate offsets and probing. By default, it is set to report in mm, but by sending a `$13=1` command, you send this boolean flag to true and these reporting features will now report in inches. `$13=0` to set back to mm.
|
||||||
|
|
||||||
|
#### $20 - Soft limits, boolean
|
||||||
|
|
||||||
|
Soft limits is a safety feature to help prevent your machine from traveling too far and beyond the limits of travel, crashing or breaking something expensive. It works by knowing the maximum travel limits for each axis and where Grbl is in machine coordinates. Whenever a new G-code motion is sent to Grbl, it checks whether or not you accidentally have exceeded your machine space. If you do, Grbl will issue an immediate feed hold wherever it is, shutdown the spindle and coolant, and then set the system alarm indicating the problem. Machine position will be retained afterwards, since it's not due to an immediate forced stop like hard limits.
|
||||||
|
|
||||||
|
NOTE: Soft limits requires homing to be enabled and accurate axis maximum travel settings, because Grbl needs to know where it is. `$20=1` to enable, and `$20=0` to disable.
|
||||||
|
|
||||||
|
#### $21 - Hard limits, boolean
|
||||||
|
|
||||||
|
Hard limit work basically the same as soft limits, but use physical switches instead. Basically you wire up some switches (mechanical, magnetic, or optical) near the end of travel of each axes, or where ever you feel that there might be trouble if your program moves too far to where it shouldn't. When the switch triggers, it will immediately halt all motion, shutdown the coolant and spindle (if connected), and go into alarm mode, which forces you to check your machine and reset everything.
|
||||||
|
|
||||||
|
To use hard limits with Grbl, the limit pins are held high with an internal pull-up resistor, so all you have to do is wire in a normally-open switch with the pin and ground and enable hard limits with `$21=1`. (Disable with `$21=0`.) We strongly advise taking electric interference prevention measures. If you want a limit for both ends of travel of one axes, just wire in two switches in parallel with the pin and ground, so if either one of them trips, it triggers the hard limit.
|
||||||
|
|
||||||
|
Keep in mind, that a hard limit event is considered to be critical event, where steppers immediately stop and will have likely have lost steps. Grbl doesn't have any feedback on position, so it can't guarantee it has any idea where it is. So, if a hard limit is triggered, Grbl will go into an infinite loop ALARM mode, giving you a chance to check your machine and forcing you to reset Grbl. Remember it's a purely a safety feature.
|
||||||
|
|
||||||
|
#### $22 - Homing cycle, boolean
|
||||||
|
|
||||||
|
Ahh, homing. For those just initiated into CNC, the homing cycle is used to accurately and precisely locate a known and consistent position on a machine every time you start up your Grbl between sessions. In other words, you know exactly where you are at any given time, every time. Say you start machining something or are about to start the next step in a job and the power goes out, you re-start Grbl and Grbl has no idea where it is. You're left with the task of figuring out where you are. If you have homing, you always have the machine zero reference point to locate from, so all you have to do is run the homing cycle and resume where you left off.
|
||||||
|
|
||||||
|
To set up the homing cycle for Grbl, you need to have limit switches in a fixed position that won't get bumped or moved, or else your reference point gets messed up. Usually they are setup in the farthest point in +x, +y, +z of each axes. Wire your limit switches in with the limit pins and ground, just like with the hard limits, and enable homing. If you're curious, you can use your limit switches for both hard limits AND homing. They play nice with each other.
|
||||||
|
|
||||||
|
By default, Grbl's homing cycle moves the Z-axis positive first to clear the workspace and then moves both the X and Y-axes at the same time in the positive direction. To set up how your homing cycle behaves, there are more Grbl settings down the page describing what they do (and compile-time options as well.)
|
||||||
|
|
||||||
|
Also, one more thing to note, when homing is enabled. Grbl will lock out all G-code commands until you perform a homing cycle. Meaning no axes motions, unless the lock is disabled ($X) but more on that later. Most, if not all CNC controllers, do something similar, as it is mostly a safety feature to prevent users from making a positioning mistake, which is very easy to do and be saddened when a mistake ruins a part. If you find this annoying or find any weird bugs, please let us know and we'll try to work on it so everyone is happy. :)
|
||||||
|
|
||||||
|
NOTE: Check out config.h for more homing options for advanced users. You can disable the homing lockout at startup, configure which axes move first during a homing cycle and in what order, and more.
|
||||||
|
|
||||||
|
|
||||||
|
#### $23 - Homing dir invert, mask
|
||||||
|
|
||||||
|
By default, Grbl assumes your homing limit switches are in the positive direction, first moving the z-axis positive, then the x-y axes positive before trying to precisely locate machine zero by going back and forth slowly around the switch. If your machine has a limit switch in the negative direction, the homing direction mask can invert the axes' direction. It works just like the step port invert and direction port invert masks, where all you have to do is send the value in the table to indicate what axes you want to invert and search for in the opposite direction.
|
||||||
|
|
||||||
|
#### $24 - Homing feed, mm/min
|
||||||
|
|
||||||
|
The homing cycle first searches for the limit switches at a higher seek rate, and after it finds them, it moves at a slower feed rate to home into the precise location of machine zero. Homing feed rate is that slower feed rate. Set this to whatever rate value that provides repeatable and precise machine zero locating.
|
||||||
|
|
||||||
|
#### $25 - Homing seek, mm/min
|
||||||
|
|
||||||
|
Homing seek rate is the homing cycle search rate, or the rate at which it first tries to find the limit switches. Adjust to whatever rate gets to the limit switches in a short enough time without crashing into your limit switches if they come in too fast.
|
||||||
|
|
||||||
|
#### $26 - Homing debounce, milliseconds
|
||||||
|
|
||||||
|
Whenever a switch triggers, some of them can have electrical/mechanical noise that actually 'bounce' the signal high and low for a few milliseconds before settling in. To solve this, you need to debounce the signal, either by hardware with some kind of signal conditioner or by software with a short delay to let the signal finish bouncing. Grbl performs a short delay, only homing when locating machine zero. Set this delay value to whatever your switch needs to get repeatable homing. In most cases, 5-25 milliseconds is fine.
|
||||||
|
|
||||||
|
#### $27 - Homing pull-off, mm
|
||||||
|
|
||||||
|
To play nice with the hard limits feature, where homing can share the same limit switches, the homing cycle will move off all of the limit switches by this pull-off travel after it completes. In other words, it helps to prevent accidental triggering of the hard limit after a homing cycle.
|
||||||
|
|
||||||
|
#### $30 - Max spindle speed, RPM
|
||||||
|
|
||||||
|
This sets the spindle speed for the maximum 5V PWM pin output. Higher programmed spindle RPMs are accepted by Grbl but the PWM output will not exceed the max 5V. By default, Grbl linearly relates the max-min RPMs to 5V-0.02V PWM pin output in 255 increments. When the PWM pin reads 0V, this indicates spindle disabled. Note that there are additional configuration options are available in config.h to tweak how this operates.
|
||||||
|
|
||||||
|
#### $31 - Min spindle speed, RPM
|
||||||
|
|
||||||
|
This sets the spindle speed for the minimum 0.02V PWM pin output (0V is disabled). Lower RPM values are accepted by Grbl but the PWM output will not go below 0.02V, except when RPM is zero. If zero, the spindle is disabled and PWM output is 0V.
|
||||||
|
|
||||||
|
#### $32 - Laser mode, boolean
|
||||||
|
|
||||||
|
When enabled, Grbl will move continuously through consecutive `G1`, `G2`, or `G3` motion commands when programmed with a `S` spindle speed (laser power). The spindle PWM pin will be updated instantaneously through each motion without stopping. However, Grbl will still stop motion if a spindle state is commanded and altered, like `M3`, `M4`, or `M5`. If the spindle needs to be disabled while under continuous motion, program a `S0`, zero spindle speed, to disable the spindle with a supported motion command.
|
||||||
|
|
||||||
|
When disabled, Grbl will operate as it always has, stopping motion with every `S` spindle speed command. This is the normal operating
|
||||||
|
|
||||||
|
#### $100, $101 and $102 – [X,Y,Z] steps/mm
|
||||||
|
|
||||||
|
Grbl needs to know how far each step will take the tool in reality. To calculate steps/mm for an axis of your machine you need to know:
|
||||||
|
|
||||||
|
* The mm traveled per revolution of your stepper motor. This is dependent on your belt drive gears or lead screw pitch.
|
||||||
|
* The full steps per revolution of your steppers (typically 200)
|
||||||
|
* The microsteps per step of your controller (typically 1, 2, 4, 8, or 16). _Tip: Using high microstep values (e.g., 16) can reduce your stepper motor torque, so use the lowest that gives you the desired axis resolution and comfortable running properties._
|
||||||
|
|
||||||
|
The steps/mm can then be calculated like this: ```steps_per_mm = (steps_per_revolution*microsteps)/mm_per_rev```
|
||||||
|
|
||||||
|
Compute this value for every axis and write these settings to Grbl.
|
||||||
|
|
||||||
|
#### $110, $111 and $112 – [X,Y,Z] Max rate, mm/min
|
||||||
|
|
||||||
|
This sets the maximum rate each axis can move. Whenever Grbl plans a move, it checks whether or not the move causes any one of these individual axes to exceed their max rate. If so, it'll slow down the motion to ensure none of the axes exceed their max rate limits. This means that each axis has its own independent speed, which is extremely useful for limiting the typically slower Z-axis.
|
||||||
|
|
||||||
|
The simplest way to determine these values is to test each axis one at a time by slowly increasing max rate settings and moving it. For example, to test the X-axis, send Grbl something like `G0 X50` with enough travel distance so that the axis accelerates to its max speed. You'll know you've hit the max rate threshold when your steppers stall. It'll make a bit of noise, but shouldn't hurt your motors. Enter a setting a 10-20% below this value, so you can account for wear, friction, and the mass of your workpiece/tool. Then, repeat for your other axes.
|
||||||
|
|
||||||
|
NOTE: This max rate setting also sets the G0 seek rates.
|
||||||
|
|
||||||
|
#### $120, $121, $122 – [X,Y,Z] Acceleration, mm/sec^2
|
||||||
|
|
||||||
|
This sets the axes acceleration parameters in mm/second/second. Simplistically, a lower value makes Grbl ease slower into motion, while a higher value yields tighter moves and reaches the desired feed rates much quicker. Much like the max rate setting, each axis has its own acceleration value and are independent of each other. This means that a multi-axis motion will only accelerate as quickly as the lowest contributing axis can.
|
||||||
|
|
||||||
|
Again, like the max rate setting, the simplest way to determine the values for this setting is to individually test each axis with slowly increasing values until the motor stalls. Then finalize your acceleration setting with a value 10-20% below this absolute max value. This should account for wear, friction, and mass inertia. We highly recommend that you dry test some G-code programs with your new settings before committing to them. Sometimes the loading on your machine is different when moving in all axes together.
|
||||||
|
|
||||||
|
|
||||||
|
#### $130, $131, $132 – [X,Y,Z] Max travel, mm
|
||||||
|
|
||||||
|
This sets the maximum travel from end to end for each axis in mm. This is only useful if you have soft limits (and homing) enabled, as this is only used by Grbl's soft limit feature to check if you have exceeded your machine limits with a motion command.
|
||||||
|
|
||||||
|
***
|
||||||
|
|
||||||
|
## Grbl's Other '$' Commands
|
||||||
|
|
||||||
|
The other `$` commands provide additional controls for the user, such as printing feedback on the current G-code parser modal state or running the homing cycle. This section explains what these commands are and how to use them.
|
||||||
|
|
||||||
|
#### `$#` - View gcode parameters
|
||||||
|
|
||||||
|
G-code parameters store the coordinate offset values for G54-G59 work coordinates, G28/G30 pre-defined positions, G92 coordinate offset, tool length offsets, and probing (not officially, but we added here anyway). Most of these parameters are directly written to EEPROM anytime they are changed and are persistent. Meaning that they will remain the same, regardless of power-down, until they are explicitly changed. The non-persistent parameters, which will are not retained when reset or power-cycled, are G92, G43.1 tool length offsets, and the G38.2 probing data.
|
||||||
|
|
||||||
|
G54-G59 work coordinates can be changed via the `G10 L2 Px` or `G10 L20 Px` command defined by the NIST gcode standard and the EMC2 (linuxcnc.org) standard. G28/G30 pre-defined positions can be changed via the `G28.1` and the `G30.1` commands, respectively.
|
||||||
|
|
||||||
|
When `$#` is called, Grbl will respond with the stored offsets from machine coordinates for each system as follows. `TLO` denotes tool length offset (for the default z-axis), and `PRB` denotes the coordinates of the last probing cycle, where the suffix `:1` denotes if the last probe was successful and `:0` as not successful.
|
||||||
|
|
||||||
|
```
|
||||||
|
[G54:4.000,0.000,0.000]
|
||||||
|
[G55:4.000,6.000,7.000]
|
||||||
|
[G56:0.000,0.000,0.000]
|
||||||
|
[G57:0.000,0.000,0.000]
|
||||||
|
[G58:0.000,0.000,0.000]
|
||||||
|
[G59:0.000,0.000,0.000]
|
||||||
|
[G28:1.000,2.000,0.000]
|
||||||
|
[G30:4.000,6.000,0.000]
|
||||||
|
[G92:0.000,0.000,0.000]
|
||||||
|
[TLO:0.000]
|
||||||
|
[PRB:0.000,0.000,0.000:0]
|
||||||
|
```
|
||||||
|
|
||||||
|
#### `$G` - View gcode parser state
|
||||||
|
|
||||||
|
This command prints all of the active gcode modes in Grbl's G-code parser. When sending this command to Grbl, it will reply with a message starting with an `[GC:` indicator like:
|
||||||
|
|
||||||
|
```
|
||||||
|
[GC:G0 G54 G17 G21 G90 G94 M0 M5 M9 T0 S0.0 F500.0]
|
||||||
|
```
|
||||||
|
|
||||||
|
These active modes determine how the next G-code block or command will be interpreted by Grbl's G-code parser. For those new to G-code and CNC machining, modes sets the parser into a particular state so you don't have to constantly tell the parser how to parse it. These modes are organized into sets called "modal groups" that cannot be logically active at the same time. For example, the units modal group sets whether your G-code program is interpreted in inches or in millimeters.
|
||||||
|
|
||||||
|
A short list of the modal groups, supported by Grbl, is shown below, but more complete and detailed descriptions can be found at LinuxCNC's [website](http://www.linuxcnc.org/docs/2.4/html/gcode_overview.html#sec:Modal-Groups). The G-code commands in **bold** indicate the default modes upon powering-up Grbl or resetting it.
|
||||||
|
|
||||||
|
| Modal Group Meaning | Member Words |
|
||||||
|
|:----:|:----:|
|
||||||
|
| Motion Mode | **G0**, G1, G2, G3, G38.2, G38.3, G38.4, G38.5, G80 |
|
||||||
|
|Coordinate System Select | **G54**, G55, G56, G57, G58, G59|
|
||||||
|
|Plane Select | **G17**, G18, G19|
|
||||||
|
|Distance Mode | **G90**, G91|
|
||||||
|
|Arc IJK Distance Mode | **G91.1** |
|
||||||
|
|Feed Rate Mode | G93, **G94**|
|
||||||
|
|Units Mode | G20, **G21**|
|
||||||
|
|Cutter Radius Compensation | **G40** |
|
||||||
|
|Tool Length Offset |G43.1, **G49**|
|
||||||
|
|Program Mode | **M0**, M1, M2, M30|
|
||||||
|
|Spindle State |M3, M4, **M5**|
|
||||||
|
|Coolant State | M7, M8, **M9** |
|
||||||
|
|
||||||
|
In addition to the G-code parser modes, Grbl will report the active `T` tool number, `S` spindle speed, and `F` feed rate, which all default to 0 upon a reset. For those that are curious, these don't quite fit into nice modal groups, but are just as important for determining the parser state.
|
||||||
|
|
||||||
|
#### `$I` - View build info
|
||||||
|
This prints feedback to the user the Grbl version and source code build date. Optionally, `$I` can also store a short string to help identify which CNC machine you are communicating with, if you have more than machine using Grbl. To set this string, send Grbl `$I=xxx`, where `xxx` is your customization string that is less than 80 characters. The next time you query Grbl with a `$I` view build info, Grbl will print this string after the version and build date.
|
||||||
|
|
||||||
|
NOTE: Some OEMs may block access to over-writing the build info string so they can store product information and codes there.
|
||||||
|
|
||||||
|
#### $N - View startup blocks
|
||||||
|
|
||||||
|
`$Nx` are the startup blocks that Grbl runs every time you power on Grbl or reset Grbl. In other words, a startup block is a line of G-code that you can have Grbl auto-magically run to set your G-code modal defaults, or anything else you need Grbl to do everytime you start up your machine. Grbl can store two blocks of G-code as a system default.
|
||||||
|
|
||||||
|
So, when connected to Grbl, type `$N` and then enter. Grbl should respond with something short like:
|
||||||
|
```
|
||||||
|
$N0=
|
||||||
|
$N1=
|
||||||
|
ok
|
||||||
|
```
|
||||||
|
Not much to go on, but this just means that there is no G-code block stored in line `$N0` for Grbl to run upon startup. `$N1` is the next line to be run.
|
||||||
|
|
||||||
|
#### $Nx=line - Save startup block
|
||||||
|
|
||||||
|
**IMPORTANT: Be very careful when storing any motion (G0/1,G2/3,G28/30) commands in the startup blocks. These motion commands will run everytime you reset or power up Grbl, so if you have an emergency situation and have to e-stop and reset, a startup block move can and will likely make things worse quickly. Also, do not place any commands that save data to EEPROM, such as G10/G28.1/G30.1. This will cause Grbl to constantly re-write this data upon every startup and reset, which will eventually wear out your Arduino's EEPROM.**
|
||||||
|
|
||||||
|
**Typical usage for a startup block is simply to set your preferred modal states, such as G20 inches mode, always default to a different work coordinate system, or, to provide a way for a user to run some user-written unique feature that they need for their crazy project.**
|
||||||
|
|
||||||
|
To set a startup block, type `$N0=` followed by a valid G-code block and an enter. Grbl will run the block to check if it's valid and then reply with an `ok` or an `error:` to tell you if it's successful or something went wrong. If there is an error, Grbl will not save it.
|
||||||
|
|
||||||
|
For example, say that you want to use your first startup block `$N0` to set your G-code parser modes like G54 work coordinate, G20 inches mode, G17 XY-plane. You would type `$N0=G20 G54 G17` with an enter and you should see an `ok` response. You can then check if it got stored by typing `$N` and you should now see a response like `$N0=G20G54G17`.
|
||||||
|
|
||||||
|
Once you have a startup block stored in Grbl's EEPROM, everytime you startup or reset you will see your startup block printed back to you, starting with an open-chevron `>`, and a `:ok` response from Grbl to indicate if it ran okay. So for the previous example, you'll see:
|
||||||
|
|
||||||
|
```
|
||||||
|
Grbl 1.1c ['$' for help]
|
||||||
|
>G20G54G17:ok
|
||||||
|
|
||||||
|
```
|
||||||
|
If you have multiple G-code startup blocks, they will print back to you in order upon every startup. And if you'd like to clear one of the startup blocks, (e.g., block 0) type `$N0=` without anything following the equal sign.
|
||||||
|
|
||||||
|
NOTE: There are two variations on when startup blocks with run. First, it will not run if Grbl initializes up in an ALARM state or exits an ALARM state via an `$X` unlock for safety reasons. Always address and cancel the ALARM and then finish by a reset, where the startup blocks will run at initialization. Second, if you have homing enabled, the startup blocks will execute immediately after a successful homing cycle, not at startup.
|
||||||
|
|
||||||
|
#### `$C` - Check gcode mode
|
||||||
|
This toggles the Grbl's gcode parser to take all incoming blocks and process them completely, as it would in normal operation, but it does not move any of the axes, ignores dwells, and powers off the spindle and coolant. This is intended as a way to provide the user a way to check how their new G-code program fares with Grbl's parser and monitor for any errors (and checks for soft limit violations, if enabled).
|
||||||
|
|
||||||
|
When toggled off, Grbl will perform an automatic soft-reset (^X). This is for two purposes. It simplifies the code management a bit. But, it also prevents users from starting a job when their G-code modes are not what they think they are. A system reset always gives the user a fresh, consistent start.
|
||||||
|
|
||||||
|
#### `$X` - Kill alarm lock
|
||||||
|
Grbl's alarm mode is a state when something has gone critically wrong, such as a hard limit or an abort during a cycle, or if Grbl doesn't know its position. By default, if you have homing enabled and power-up the Arduino, Grbl enters the alarm state, because it does not know its position. The alarm mode will lock all G-code commands until the '$H' homing cycle has been performed. Or if a user needs to override the alarm lock to move their axes off their limit switches, for example, '$X' kill alarm lock will override the locks and allow G-code functions to work again.
|
||||||
|
|
||||||
|
But, tread carefully!! This should only be used in emergency situations. The position has likely been lost, and Grbl may not be where you think it is. So, it's advised to use G91 incremental mode to make short moves. Then, perform a homing cycle or reset immediately afterwards.
|
||||||
|
|
||||||
|
As noted earlier, startup lines do not execute after a `$X` command. Always reset when you have cleared the alarm and fixed the scenario that caused it. When Grbl resets to idle, the startup lines will then run as normal.
|
||||||
|
|
||||||
|
#### `$H` - Run homing cycle
|
||||||
|
This command is the only way to perform the homing cycle in Grbl. Some other motion controllers designate a special G-code command to run a homing cycle, but this is incorrect according to the G-code standards. Homing is a completely separate command handled by the controller.
|
||||||
|
|
||||||
|
TIP: After running a homing cycle, rather jogging manually all the time to a position in the middle of your workspace volume. You can set a G28 or G30 pre-defined position to be your post-homing position, closer to where you'll be machining. To set these, you'll first need to jog your machine to where you would want it to move to after homing. Type G28.1 (or G30.1) to have Grbl store that position. So then after '$H' homing, you could just enter 'G28' (or 'G30') and it'll move there auto-magically. In general, I would just move the XY axis to the center and leave the Z-axis up. This ensures that there isn't a chance the tool in the spindle will interfere and that it doesn't catch on anything.
|
||||||
|
|
||||||
|
#### `$Jx=line` - Run jogging motion
|
||||||
|
|
||||||
|
New to Grbl v1.1, this command will execute a special jogging motion. There are three main differences between a jogging motion and a motion commanded by a g-code line.
|
||||||
|
|
||||||
|
- Like normal g-code commands, several jog motions may be queued into the planner buffer, but the jogging can be easily canceled by a jog-cancel or feed-hold real-time command. Grbl will immediately hold the current jog and then automatically purge the buffers of any remaining commands.
|
||||||
|
- Jog commands are completely independent of the g-code parser state. It will not change any modes like `G91` incremental distance mode. So, you no longer have to make sure that you change it back to `G90` absolute distance mode afterwards. This helps reduce the chance of starting with the wrong g-code modes enabled.
|
||||||
|
- If soft-limits are enabled, any jog command that exceeds a soft-limit will simply return an error. It will not throw an alarm as it would with a normal g-code command. This allows for a much more enjoyable and fluid GUI or joystick interaction.
|
||||||
|
|
||||||
|
Executing a jog requires a specific command structure, as described below:
|
||||||
|
|
||||||
|
- The first three characters must be '$J=' to indicate the jog.
|
||||||
|
- The jog command follows immediate after the '=' and works like a normal G1 command.
|
||||||
|
- Feed rate is only interpreted in G94 units per minute. A prior G93 state is ignored during jog.
|
||||||
|
- Required words:
|
||||||
|
- XYZ: One or more axis words with target value.
|
||||||
|
- F - Feed rate value. NOTE: Each jog requires this value and is not treated as modal.
|
||||||
|
- 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.
|
||||||
|
- G20 or G21 - Inch and millimeter mode
|
||||||
|
- G90 or G91 - Absolute and incremental distances
|
||||||
|
- G53 - Move in machine coordinates
|
||||||
|
- All other g-codes, m-codes, and value words are not accepted in the jog command.
|
||||||
|
- Spaces and comments are allowed in the command. These are removed by the pre-parser.
|
||||||
|
|
||||||
|
- Example: G21 and G90 are active modal states prior to jogging. These are sequential commands.
|
||||||
|
- `$J=X10.0 Y-1.5` will move to X=10.0mm and Y=-1.5mm in work coordinate frame (WPos).
|
||||||
|
- `$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.
|
||||||
|
- `$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).
|
||||||
|
|
||||||
|
Jog commands behave almost identically to normal g-code streaming. Every jog command will
|
||||||
|
return an 'ok' when the jogging motion has been parsed and is setup for execution. If a
|
||||||
|
command is not valid or exceeds a soft-limit, Grbl will return an 'error:'. Multiple jogging commands may be queued in sequence.
|
||||||
|
|
||||||
|
NOTE: See additional jogging documentation for details on using this command to create a low-latency joystick or rotary dial interface.
|
||||||
|
|
||||||
|
|
||||||
|
#### `$RST=$`, `$RST=#`, and `$RST=*`- Restore Grbl settings and data to defaults
|
||||||
|
These commands are not listed in the main Grbl `$` help message, but are available to allow users to restore parts of or all of Grbl's EEPROM data. Note: Grbl will automatically reset after executing one of these commands to ensure the system is initialized correctly.
|
||||||
|
|
||||||
|
- `$RST=$` : Erases and restores the `$$` Grbl settings back to defaults, which is defined by the default settings file used when compiling Grbl. Often OEMs will build their Grbl firmwares with their machine-specific recommended settings. This provides users and OEMs a quick way to get back to square-one, if something went awry or if a user wants to start over.
|
||||||
|
- `$RST=#` : Erases and zeros all G54-G59 work coordinate offsets and G28/30 positions stored in EEPROM. These are generally the values seen in the `$#` parameters printout. This provides an easy way to clear these without having to do it manually for each set with a `G20 L2/20` or `G28.1/30.1` command.
|
||||||
|
- `$RST=*` : This clears and restores all of the EEPROM data used by Grbl. This includes `$$` settings, `$#` parameters, `$N` startup lines, and `$I` build info string. Note that this doesn't wipe the entire EEPROM, only the data areas Grbl uses. To do a complete wipe, please use the Arduino IDE's EEPROM clear example project.
|
||||||
|
|
||||||
|
NOTE: Some OEMs may restrict some or all of these commands to prevent certain data they use from being wiped.
|
||||||
|
|
||||||
|
#### `$SLP` - Enable Sleep Mode
|
||||||
|
|
||||||
|
This command will place Grbl into a de-powered sleep state, shutting down the spindle, coolant, and stepper enable pins and block any commands. It may only be exited by a soft-reset or power-cycle. Once re-initialized, Grbl will automatically enter an ALARM state, because it's not sure where it is due to the steppers being disabled.
|
||||||
|
|
||||||
|
This feature is useful if you need to automatically de-power everything at the end of a job by adding this command at the end of your g-code program, BUT, it is highly recommended that you add commands to first move your machine to a safe parking location prior to this sleep command. It also should be emphasized that you should have a reliable CNC machine that will disable everything when its supposed to, like your spindle. Grbl is not responsible for any damage it may cause. It's never a good idea to leave your machine unattended. So, use this command with the utmost caution!
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
***
|
||||||
|
|
||||||
|
## Other Resources:
|
||||||
|
|
355
grbl/config.h
355
grbl/config.h
@ -2,7 +2,7 @@
|
|||||||
config.h - compile time configuration
|
config.h - compile time configuration
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -18,7 +18,7 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// This file contains compile-time configurations for Grbl's internal system. For the most part,
|
// This file contains compile-time configurations for Grbl's internal system. For the most part,
|
||||||
// users will not need to directly modify these, but they are here for specific needs, i.e.
|
// users will not need to directly modify these, but they are here for specific needs, i.e.
|
||||||
// performance tuning or adjusting to non-typical machines.
|
// performance tuning or adjusting to non-typical machines.
|
||||||
@ -38,19 +38,49 @@
|
|||||||
#define CPU_MAP_ATMEGA328P // Arduino Uno CPU
|
#define CPU_MAP_ATMEGA328P // Arduino Uno CPU
|
||||||
|
|
||||||
// Serial baud rate
|
// Serial baud rate
|
||||||
|
// #define BAUD_RATE 230400
|
||||||
#define BAUD_RATE 115200
|
#define BAUD_RATE 115200
|
||||||
|
|
||||||
// Define realtime command special characters. These characters are 'picked-off' directly from the
|
// Define realtime command special characters. These characters are 'picked-off' directly from the
|
||||||
// serial read data stream and are not passed to the grbl line execution parser. Select characters
|
// serial read data stream and are not passed to the grbl line execution parser. Select characters
|
||||||
// that do not and must not exist in the streamed g-code program. ASCII control characters may be
|
// that do not and must not exist in the streamed g-code program. ASCII control characters may be
|
||||||
// used, if they are available per user setup. Also, extended ASCII codes (>127), which are never in
|
// used, if they are available per user setup. Also, extended ASCII codes (>127), which are never in
|
||||||
// g-code programs, maybe selected for interface programs.
|
// g-code programs, maybe selected for interface programs.
|
||||||
// NOTE: If changed, manually update help message in report.c.
|
// NOTE: If changed, manually update help message in report.c.
|
||||||
#define CMD_STATUS_REPORT '?'
|
|
||||||
#define CMD_FEED_HOLD '!'
|
|
||||||
#define CMD_CYCLE_START '~'
|
|
||||||
#define CMD_RESET 0x18 // ctrl-x.
|
#define CMD_RESET 0x18 // ctrl-x.
|
||||||
#define CMD_SAFETY_DOOR '@'
|
#define CMD_STATUS_REPORT '?'
|
||||||
|
#define CMD_CYCLE_START '~'
|
||||||
|
#define CMD_FEED_HOLD '!'
|
||||||
|
|
||||||
|
// NOTE: All override realtime commands must be in the extended ASCII character set, starting
|
||||||
|
// at character value 128 (0x80) and up to 255 (0xFF). If the normal set of realtime commands,
|
||||||
|
// such as status reports, feed hold, reset, and cycle start, are moved to the extended set
|
||||||
|
// space, serial.c's RX ISR will need to be modified to accomodate the change.
|
||||||
|
// #define CMD_RESET 0x80
|
||||||
|
// #define CMD_STATUS_REPORT 0x81
|
||||||
|
// #define CMD_CYCLE_START 0x82
|
||||||
|
// #define CMD_FEED_HOLD 0x83
|
||||||
|
#define CMD_SAFETY_DOOR 0x84
|
||||||
|
#define CMD_JOG_CANCEL 0x85
|
||||||
|
#define CMD_DEBUG_REPORT 0x86 // Only when DEBUG enabled, sends debug report in '{}' braces.
|
||||||
|
#define CMD_FEED_OVR_RESET 0x90 // Restores feed override value to 100%.
|
||||||
|
#define CMD_FEED_OVR_COARSE_PLUS 0x91
|
||||||
|
#define CMD_FEED_OVR_COARSE_MINUS 0x92
|
||||||
|
#define CMD_FEED_OVR_FINE_PLUS 0x93
|
||||||
|
#define CMD_FEED_OVR_FINE_MINUS 0x94
|
||||||
|
#define CMD_RAPID_OVR_RESET 0x95 // Restores rapid override value to 100%.
|
||||||
|
#define CMD_RAPID_OVR_MEDIUM 0x96
|
||||||
|
#define CMD_RAPID_OVR_LOW 0x97
|
||||||
|
// #define CMD_RAPID_OVR_EXTRA_LOW 0x98 // *NOT SUPPORTED*
|
||||||
|
#define CMD_SPINDLE_OVR_RESET 0x99 // Restores spindle override value to 100%.
|
||||||
|
#define CMD_SPINDLE_OVR_COARSE_PLUS 0x9A
|
||||||
|
#define CMD_SPINDLE_OVR_COARSE_MINUS 0x9B
|
||||||
|
#define CMD_SPINDLE_OVR_FINE_PLUS 0x9C
|
||||||
|
#define CMD_SPINDLE_OVR_FINE_MINUS 0x9D
|
||||||
|
#define CMD_SPINDLE_OVR_STOP 0x9E
|
||||||
|
#define CMD_COOLANT_FLOOD_OVR_TOGGLE 0xA0
|
||||||
|
#define CMD_COOLANT_MIST_OVR_TOGGLE 0xA1
|
||||||
|
|
||||||
// If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces
|
// If homing is enabled, homing init lock sets Grbl into an alarm state upon power up. This forces
|
||||||
// the user to perform the homing cycle (or override the locks) before doing anything else. This is
|
// the user to perform the homing cycle (or override the locks) before doing anything else. This is
|
||||||
@ -59,17 +89,17 @@
|
|||||||
|
|
||||||
// Define the homing cycle patterns with bitmasks. The homing cycle first performs a search mode
|
// Define the homing cycle patterns with bitmasks. The homing cycle first performs a search mode
|
||||||
// to quickly engage the limit switches, followed by a slower locate mode, and finished by a short
|
// to quickly engage the limit switches, followed by a slower locate mode, and finished by a short
|
||||||
// pull-off motion to disengage the limit switches. The following HOMING_CYCLE_x defines are executed
|
// pull-off motion to disengage the limit switches. The following HOMING_CYCLE_x defines are executed
|
||||||
// in order starting with suffix 0 and completes the homing routine for the specified-axes only. If
|
// in order starting with suffix 0 and completes the homing routine for the specified-axes only. If
|
||||||
// an axis is omitted from the defines, it will not home, nor will the system update its position.
|
// an axis is omitted from the defines, it will not home, nor will the system update its position.
|
||||||
// Meaning that this allows for users with non-standard cartesian machines, such as a lathe (x then z,
|
// Meaning that this allows for users with non-standard cartesian machines, such as a lathe (x then z,
|
||||||
// with no y), to configure the homing cycle behavior to their needs.
|
// with no y), to configure the homing cycle behavior to their needs.
|
||||||
// NOTE: The homing cycle is designed to allow sharing of limit pins, if the axes are not in the same
|
// NOTE: The homing cycle is designed to allow sharing of limit pins, if the axes are not in the same
|
||||||
// cycle, but this requires some pin settings changes in cpu_map.h file. For example, the default homing
|
// cycle, but this requires some pin settings changes in cpu_map.h file. For example, the default homing
|
||||||
// cycle can share the Z limit pin with either X or Y limit pins, since they are on different cycles.
|
// cycle can share the Z limit pin with either X or Y limit pins, since they are on different cycles.
|
||||||
// By sharing a pin, this frees up a precious IO pin for other purposes. In theory, all axes limit pins
|
// By sharing a pin, this frees up a precious IO pin for other purposes. In theory, all axes limit pins
|
||||||
// may be reduced to one pin, if all axes are homed with seperate cycles, or vice versa, all three axes
|
// may be reduced to one pin, if all axes are homed with seperate cycles, or vice versa, all three axes
|
||||||
// on separate pin, but homed in one cycle. Also, it should be noted that the function of hard limits
|
// on separate pin, but homed in one cycle. Also, it should be noted that the function of hard limits
|
||||||
// will not be affected by pin sharing.
|
// will not be affected by pin sharing.
|
||||||
// NOTE: Defaults are set for a traditional 3-axis CNC machine. Z-axis first to clear, followed by X & Y.
|
// NOTE: Defaults are set for a traditional 3-axis CNC machine. Z-axis first to clear, followed by X & Y.
|
||||||
#define HOMING_CYCLE_0 (1<<Z_AXIS) // REQUIRED: First move Z to clear workspace.
|
#define HOMING_CYCLE_0 (1<<Z_AXIS) // REQUIRED: First move Z to clear workspace.
|
||||||
@ -77,12 +107,12 @@
|
|||||||
// #define HOMING_CYCLE_2 // OPTIONAL: Uncomment and add axes mask to enable
|
// #define HOMING_CYCLE_2 // OPTIONAL: Uncomment and add axes mask to enable
|
||||||
|
|
||||||
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
// Number of homing cycles performed after when the machine initially jogs to limit switches.
|
||||||
// This help in preventing overshoot and should improve repeatability. This value should be one or
|
// This help in preventing overshoot and should improve repeatability. This value should be one or
|
||||||
// greater.
|
// greater.
|
||||||
#define N_HOMING_LOCATE_CYCLE 1 // Integer (1-128)
|
#define N_HOMING_LOCATE_CYCLE 1 // Integer (1-128)
|
||||||
|
|
||||||
// After homing, Grbl will set by default the entire machine space into negative space, as is typical
|
// After homing, Grbl will set by default the entire machine space into negative space, as is typical
|
||||||
// for professional CNC machines, regardless of where the limit switches are located. Uncomment this
|
// for professional CNC machines, regardless of where the limit switches are located. Uncomment this
|
||||||
// define to force Grbl to always set the machine origin at the homed location despite switch orientation.
|
// define to force Grbl to always set the machine origin at the homed location despite switch orientation.
|
||||||
// #define HOMING_FORCE_SET_ORIGIN // Uncomment to enable.
|
// #define HOMING_FORCE_SET_ORIGIN // Uncomment to enable.
|
||||||
|
|
||||||
@ -92,7 +122,7 @@
|
|||||||
// parser state depending on user preferences.
|
// parser state depending on user preferences.
|
||||||
#define N_STARTUP_LINE 2 // Integer (1-2)
|
#define N_STARTUP_LINE 2 // Integer (1-2)
|
||||||
|
|
||||||
// Number of floating decimal points printed by Grbl for certain value types. These settings are
|
// Number of floating decimal points printed by Grbl for certain value types. These settings are
|
||||||
// determined by realistic and commonly observed values in CNC machines. For example, position
|
// determined by realistic and commonly observed values in CNC machines. For example, position
|
||||||
// values cannot be less than 0.001mm or 0.0001in, because machines can not be physically more
|
// values cannot be less than 0.001mm or 0.0001in, because machines can not be physically more
|
||||||
// precise this. So, there is likely no need to change these, but you can if you need to here.
|
// precise this. So, there is likely no need to change these, but you can if you need to here.
|
||||||
@ -106,29 +136,24 @@
|
|||||||
|
|
||||||
// If your machine has two limits switches wired in parallel to one axis, you will need to enable
|
// If your machine has two limits switches wired in parallel to one axis, you will need to enable
|
||||||
// this feature. Since the two switches are sharing a single pin, there is no way for Grbl to tell
|
// this feature. Since the two switches are sharing a single pin, there is no way for Grbl to tell
|
||||||
// which one is enabled. This option only effects homing, where if a limit is engaged, Grbl will
|
// which one is enabled. This option only effects homing, where if a limit is engaged, Grbl will
|
||||||
// alarm out and force the user to manually disengage the limit switch. Otherwise, if you have one
|
// alarm out and force the user to manually disengage the limit switch. Otherwise, if you have one
|
||||||
// limit switch for each axis, don't enable this option. By keeping it disabled, you can perform a
|
// limit switch for each axis, don't enable this option. By keeping it disabled, you can perform a
|
||||||
// homing cycle while on the limit switch and not have to move the machine off of it.
|
// homing cycle while on the limit switch and not have to move the machine off of it.
|
||||||
// #define LIMITS_TWO_SWITCHES_ON_AXES
|
// #define LIMITS_TWO_SWITCHES_ON_AXES
|
||||||
|
|
||||||
// Allows GRBL to track and report gcode line numbers. Enabling this means that the planning buffer
|
// Allows GRBL to track and report gcode line numbers. Enabling this means that the planning buffer
|
||||||
// goes from 18 or 16 to make room for the additional line number data in the plan_block_t struct
|
// goes from 16 to 15 to make room for the additional line number data in the plan_block_t struct
|
||||||
// #define USE_LINE_NUMBERS // Disabled by default. Uncomment to enable.
|
// #define USE_LINE_NUMBERS // Disabled by default. Uncomment to enable.
|
||||||
|
|
||||||
// Allows GRBL to report the real-time feed rate. Enabling this means that GRBL will be reporting more
|
|
||||||
// data with each status update.
|
|
||||||
// NOTE: This is experimental and doesn't quite work 100%. Maybe fixed or refactored later.
|
|
||||||
// #define REPORT_REALTIME_RATE // Disabled by default. Uncomment to enable.
|
|
||||||
|
|
||||||
// Upon a successful probe cycle, this option provides immediately feedback of the probe coordinates
|
// Upon a successful probe cycle, this option provides immediately feedback of the probe coordinates
|
||||||
// through an automatically generated message. If disabled, users can still access the last probe
|
// through an automatically generated message. If disabled, users can still access the last probe
|
||||||
// coordinates through Grbl '$#' print parameters.
|
// coordinates through Grbl '$#' print parameters.
|
||||||
#define MESSAGE_PROBE_COORDINATES // Enabled by default. Comment to disable.
|
#define MESSAGE_PROBE_COORDINATES // Enabled by default. Comment to disable.
|
||||||
|
|
||||||
// Enables a second coolant control pin via the mist coolant g-code command M7 on the Arduino Uno
|
// Enables a second coolant control pin via the mist coolant g-code command M7 on the Arduino Uno
|
||||||
// analog pin 4. Only use this option if you require a second coolant control pin.
|
// analog pin 4. Only use this option if you require a second coolant control pin.
|
||||||
// NOTE: The M8 flood coolant control pin on analog pin 4 will still be functional regardless.
|
// NOTE: The M8 flood coolant control pin on analog pin 3 will still be functional regardless.
|
||||||
// #define ENABLE_M7 // Disabled by default. Uncomment to enable.
|
// #define ENABLE_M7 // Disabled by default. Uncomment to enable.
|
||||||
|
|
||||||
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
|
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
|
||||||
@ -142,12 +167,12 @@
|
|||||||
#define SAFETY_DOOR_SPINDLE_DELAY 4.0 // Float (seconds)
|
#define SAFETY_DOOR_SPINDLE_DELAY 4.0 // Float (seconds)
|
||||||
#define SAFETY_DOOR_COOLANT_DELAY 1.0 // Float (seconds)
|
#define SAFETY_DOOR_COOLANT_DELAY 1.0 // Float (seconds)
|
||||||
|
|
||||||
// Enable CoreXY kinematics. Use ONLY with CoreXY machines.
|
// Enable CoreXY kinematics. Use ONLY with CoreXY machines.
|
||||||
// IMPORTANT: If homing is enabled, you must reconfigure the homing cycle #defines above to
|
// IMPORTANT: If homing is enabled, you must reconfigure the homing cycle #defines above to
|
||||||
// #define HOMING_CYCLE_0 (1<<X_AXIS) and #define HOMING_CYCLE_1 (1<<Y_AXIS)
|
// #define HOMING_CYCLE_0 (1<<X_AXIS) and #define HOMING_CYCLE_1 (1<<Y_AXIS)
|
||||||
// NOTE: This configuration option alters the motion of the X and Y axes to principle of operation
|
// NOTE: This configuration option alters the motion of the X and Y axes to principle of operation
|
||||||
// defined at (http://corexy.com/theory.html). Motors are assumed to positioned and wired exactly as
|
// defined at (http://corexy.com/theory.html). Motors are assumed to positioned and wired exactly as
|
||||||
// described, if not, motions may move in strange directions. Grbl assumes the CoreXY A and B motors
|
// described, if not, motions may move in strange directions. Grbl requires the CoreXY A and B motors
|
||||||
// have the same steps per mm internally.
|
// have the same steps per mm internally.
|
||||||
// #define COREXY // Default disabled. Uncomment to enable.
|
// #define COREXY // Default disabled. Uncomment to enable.
|
||||||
|
|
||||||
@ -158,8 +183,8 @@
|
|||||||
// #define INVERT_CONTROL_PIN_MASK CONTROL_MASK // Default disabled. Uncomment to disable.
|
// #define INVERT_CONTROL_PIN_MASK CONTROL_MASK // Default disabled. Uncomment to disable.
|
||||||
// #define INVERT_CONTROL_PIN_MASK ((1<<CONTROL_SAFETY_DOOR_BIT)|(CONTROL_RESET_BIT)) // Default disabled.
|
// #define INVERT_CONTROL_PIN_MASK ((1<<CONTROL_SAFETY_DOOR_BIT)|(CONTROL_RESET_BIT)) // Default disabled.
|
||||||
|
|
||||||
// Inverts select limit pin states based on the following mask. This effects all limit pin functions,
|
// Inverts select limit pin states based on the following mask. This effects all limit pin functions,
|
||||||
// such as hard limits and homing. However, this is different from overall invert limits setting.
|
// such as hard limits and homing. However, this is different from overall invert limits setting.
|
||||||
// This build option will invert only the limit pins defined here, and then the invert limits setting
|
// This build option will invert only the limit pins defined here, and then the invert limits setting
|
||||||
// will be applied to all of them. This is useful when a user has a mixed set of limit pins with both
|
// will be applied to all of them. This is useful when a user has a mixed set of limit pins with both
|
||||||
// normally-open(NO) and normally-closed(NC) switches installed on their machine.
|
// normally-open(NO) and normally-closed(NC) switches installed on their machine.
|
||||||
@ -168,52 +193,119 @@
|
|||||||
|
|
||||||
// Inverts the spindle enable pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
|
// Inverts the spindle enable pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
|
||||||
// for some pre-built electronic boards.
|
// for some pre-built electronic boards.
|
||||||
// NOTE: If VARIABLE_SPINDLE is enabled(default), this option has no effect as the PWM output and
|
// NOTE: If VARIABLE_SPINDLE is enabled(default), this option has no effect as the PWM output and
|
||||||
// spindle enable are combined to one pin. If you need both this option and spindle speed PWM,
|
// spindle enable are combined to one pin. If you need both this option and spindle speed PWM,
|
||||||
// uncomment the config option USE_SPINDLE_DIR_AS_ENABLE_PIN below.
|
// uncomment the config option USE_SPINDLE_DIR_AS_ENABLE_PIN below.
|
||||||
// #define INVERT_SPINDLE_ENABLE_PIN // Default disabled. Uncomment to enable.
|
// #define INVERT_SPINDLE_ENABLE_PIN // Default disabled. Uncomment to enable.
|
||||||
|
|
||||||
// Enable all pin states feedback in status reports. Configurable with Grbl settings to print only
|
// Inverts the selected coolant pin from low-disabled/high-enabled to low-enabled/high-disabled. Useful
|
||||||
// the desired data, which is presented as simple binary reading of each pin as (0 (low) or 1(high)).
|
// for some pre-built electronic boards.
|
||||||
// The fields are printed in a particular order and settings groups are separated by '|' characters.
|
// #define INVERT_COOLANT_FLOOD_PIN // Default disabled. Uncomment to enable.
|
||||||
// NOTE: This option is here for backward compatibility of the old style of pin state reports, i.e.
|
// #define INVERT_COOLANT_MIST_PIN // Default disabled. Note: Enable M7 mist coolant in config.h
|
||||||
// `Lim:000`. This new `Pin:` report will be the standard going forward.
|
|
||||||
#define REPORT_ALL_PIN_STATES // Default enabled. Comment to disable.
|
|
||||||
|
|
||||||
// When Grbl powers-cycles or is hard reset with the Arduino reset button, Grbl boots up with no ALARM
|
// When Grbl powers-cycles or is hard reset with the Arduino reset button, Grbl boots up with no ALARM
|
||||||
// by default. This is to make it as simple as possible for new users to start using Grbl. When homing
|
// by default. This is to make it as simple as possible for new users to start using Grbl. When homing
|
||||||
// is enabled and a user has installed limit switches, Grbl will boot up in an ALARM state to indicate
|
// is enabled and a user has installed limit switches, Grbl will boot up in an ALARM state to indicate
|
||||||
// Grbl doesn't know its position and to force the user to home before proceeding. This option forces
|
// Grbl doesn't know its position and to force the user to home before proceeding. This option forces
|
||||||
// Grbl to always initialize into an ALARM state regardless of homing or not. This option is more for
|
// Grbl to always initialize into an ALARM state regardless of homing or not. This option is more for
|
||||||
// OEMs and LinuxCNC users that would like this power-cycle behavior.
|
// OEMs and LinuxCNC users that would like this power-cycle behavior.
|
||||||
// #define FORCE_INITIALIZATION_ALARM // Default disabled. Uncomment to enable.
|
// #define FORCE_INITIALIZATION_ALARM // Default disabled. Uncomment to enable.
|
||||||
|
|
||||||
|
// At power-up or a reset, Grbl will check the limit switch states to ensure they are not active
|
||||||
|
// before initialization. If it detects a problem and the hard limits setting is enabled, Grbl will
|
||||||
|
// simply message the user to check the limits and enter an alarm state, rather than idle. Grbl will
|
||||||
|
// not throw an alarm message.
|
||||||
|
#define CHECK_LIMITS_AT_INIT
|
||||||
|
|
||||||
// ---------------------------------------------------------------------------------------
|
// ---------------------------------------------------------------------------------------
|
||||||
// ADVANCED CONFIGURATION OPTIONS:
|
// ADVANCED CONFIGURATION OPTIONS:
|
||||||
|
|
||||||
|
// Enables code for debugging purposes. Not for general use and always in constant flux.
|
||||||
|
// #define DEBUG // Uncomment to enable. Default disabled.
|
||||||
|
|
||||||
|
// Configure rapid, feed, and spindle override settings. These values define the max and min
|
||||||
|
// allowable override values and the coarse and fine increments per command received. Please
|
||||||
|
// note the allowable values in the descriptions following each define.
|
||||||
|
#define DEFAULT_FEED_OVERRIDE 100 // 100%. Don't change this value.
|
||||||
|
#define MAX_FEED_RATE_OVERRIDE 200 // Percent of programmed feed rate (100-255). Usually 120% or 200%
|
||||||
|
#define MIN_FEED_RATE_OVERRIDE 10 // Percent of programmed feed rate (1-100). Usually 50% or 1%
|
||||||
|
#define FEED_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
|
||||||
|
#define FEED_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
|
||||||
|
|
||||||
|
#define DEFAULT_RAPID_OVERRIDE 100 // 100%. Don't change this value.
|
||||||
|
#define RAPID_OVERRIDE_MEDIUM 50 // Percent of rapid (1-99). Usually 50%.
|
||||||
|
#define RAPID_OVERRIDE_LOW 25 // Percent of rapid (1-99). Usually 25%.
|
||||||
|
// #define RAPID_OVERRIDE_EXTRA_LOW 5 // *NOT SUPPORTED* Percent of rapid (1-99). Usually 5%.
|
||||||
|
|
||||||
|
#define DEFAULT_SPINDLE_SPEED_OVERRIDE 100 // 100%. Don't change this value.
|
||||||
|
#define MAX_SPINDLE_SPEED_OVERRIDE 200 // Percent of programmed spindle speed (100-255). Usually 200%.
|
||||||
|
#define MIN_SPINDLE_SPEED_OVERRIDE 50 // Percent of programmed spindle speed (1-100). Usually 50%.
|
||||||
|
#define SPINDLE_OVERRIDE_COARSE_INCREMENT 10 // (1-99). Usually 10%.
|
||||||
|
#define SPINDLE_OVERRIDE_FINE_INCREMENT 1 // (1-99). Usually 1%.
|
||||||
|
|
||||||
|
// When a M2 or M30 program end command is executed, most g-code states are restored to their defaults.
|
||||||
|
// This compile-time option includes the restoring of the feed, rapid, and spindle speed override values
|
||||||
|
// to their default values at program end.
|
||||||
|
#define RESTORE_OVERRIDES_AFTER_PROGRAM_END // Default enabled. Comment to disable.
|
||||||
|
|
||||||
// Enables minimal reporting feedback mode for GUIs, where human-readable strings are not as important.
|
// Enables minimal reporting feedback mode for GUIs, where human-readable strings are not as important.
|
||||||
// This saves nearly 2KB of flash space and may allow enough space to install other/future features.
|
// This saves nearly 2KB of flash space and may allow enough space to install other/future features.
|
||||||
// GUIs will need to install a look-up table for the error-codes that Grbl sends back in their place.
|
// GUIs will need to install a look-up table for the error-codes that Grbl sends back in their place.
|
||||||
// NOTE: This feature is new and experimental. Make sure the GUI you are using supports this mode.
|
// NOTE: This feature is new and experimental. Make sure the GUI you are using supports this mode.
|
||||||
// #define REPORT_GUI_MODE // Default disabled. Uncomment to enable.
|
#define REPORT_GUI_MODE // Default enabled. Comment to disable.
|
||||||
|
|
||||||
|
// The status report change for Grbl v1.0 and after also removed the ability to disable/enable most data
|
||||||
|
// fields from the report. This caused issues for GUI developers, who've had to manage several scenarios
|
||||||
|
// and configurations. The increased efficiency of the new reporting style allows for all data fields to
|
||||||
|
// be sent without potential performance issues.
|
||||||
|
// NOTE: The options below are here only provide a way to disable certain data fields if a unique
|
||||||
|
// situation demands it, but be aware GUIs may depend on this data. If disabled, it may not be compatible.
|
||||||
|
#define REPORT_FIELD_BUFFER_STATE // Default enabled. Comment to disable.
|
||||||
|
#define REPORT_FIELD_PIN_STATE // Default enabled. Comment to disable.
|
||||||
|
#define REPORT_FIELD_CURRENT_RATE // Default enabled. Comment to disable.
|
||||||
|
#define REPORT_FIELD_WORK_COORD_OFFSET // Default enabled. Comment to disable.
|
||||||
|
#define REPORT_FIELD_OVERRIDES // Default enabled. Comment to disable.
|
||||||
|
#define REPORT_FIELD_LINE_NUMBERS // Default enabled. Comment to disable.
|
||||||
|
|
||||||
|
// Some status report data isn't necessary for realtime, only intermittently, because the values don't
|
||||||
|
// change often. The following macros configures how many times a status report needs to be called before
|
||||||
|
// the associated data is refreshed and included in the status report. However, if one of these value
|
||||||
|
// changes, Grbl will automatically include this data in the next status report, regardless of what the
|
||||||
|
// count is at the time. This helps reduce the communication overhead involved with high frequency reporting
|
||||||
|
// and agressive streaming. There is also a busy and an idle refresh count, which sets up Grbl to send
|
||||||
|
// refreshes more often when its not doing anything important. With a good GUI, this data doesn't need
|
||||||
|
// to be refreshed very often, on the order of a several seconds.
|
||||||
|
// NOTE: The refresh count cannot be set to zero and must be one or greater.
|
||||||
|
#define REPORT_OVR_REFRESH_BUSY_COUNT 20 // (1-255)
|
||||||
|
#define REPORT_OVR_REFRESH_IDLE_COUNT 10 // (1-255) Must be less than or equal to the busy count
|
||||||
|
#define REPORT_WCO_REFRESH_BUSY_COUNT 30 // (1-255)
|
||||||
|
#define REPORT_WCO_REFRESH_IDLE_COUNT 10 // (1-255) Must be less than or equal to the busy count
|
||||||
|
|
||||||
|
// COMPATIBILITY OPTIONS:
|
||||||
|
// Grbl v1.0 and later altered the formatting of the realtime status reports to make it more consistent
|
||||||
|
// for parsing with cleaner delimiters and optimized messages. To use Grbl v0.9-style status reporting,
|
||||||
|
// enable this compile option. This is generally useful if older GUIs require this formatting.
|
||||||
|
// #define USE_CLASSIC_REALTIME_REPORT
|
||||||
|
// #define REPORT_ALL_PIN_STATES // Default disabled. Comment to enable. NOTE: Compatible with old-style reports only.
|
||||||
|
// #define REPORT_REALTIME_RATE // Disabled by default. Uncomment to enable.
|
||||||
|
|
||||||
// The temporal resolution of the acceleration management subsystem. A higher number gives smoother
|
// The temporal resolution of the acceleration management subsystem. A higher number gives smoother
|
||||||
// acceleration, particularly noticeable on machines that run at very high feedrates, but may negatively
|
// acceleration, particularly noticeable on machines that run at very high feedrates, but may negatively
|
||||||
// impact performance. The correct value for this parameter is machine dependent, so it's advised to
|
// impact performance. The correct value for this parameter is machine dependent, so it's advised to
|
||||||
// set this only as high as needed. Approximate successful values can widely range from 50 to 200 or more.
|
// set this only as high as needed. Approximate successful values can widely range from 50 to 200 or more.
|
||||||
// NOTE: Changing this value also changes the execution time of a segment in the step segment buffer.
|
// NOTE: Changing this value also changes the execution time of a segment in the step segment buffer.
|
||||||
// When increasing this value, this stores less overall time in the segment buffer and vice versa. Make
|
// When increasing this value, this stores less overall time in the segment buffer and vice versa. Make
|
||||||
// certain the step segment buffer is increased/decreased to account for these changes.
|
// certain the step segment buffer is increased/decreased to account for these changes.
|
||||||
#define ACCELERATION_TICKS_PER_SECOND 100
|
#define ACCELERATION_TICKS_PER_SECOND 100
|
||||||
|
|
||||||
// Adaptive Multi-Axis Step Smoothing (AMASS) is an advanced feature that does what its name implies,
|
// Adaptive Multi-Axis Step Smoothing (AMASS) is an advanced feature that does what its name implies,
|
||||||
// smoothing the stepping of multi-axis motions. This feature smooths motion particularly at low step
|
// smoothing the stepping of multi-axis motions. This feature smooths motion particularly at low step
|
||||||
// frequencies below 10kHz, where the aliasing between axes of multi-axis motions can cause audible
|
// frequencies below 10kHz, where the aliasing between axes of multi-axis motions can cause audible
|
||||||
// noise and shake your machine. At even lower step frequencies, AMASS adapts and provides even better
|
// noise and shake your machine. At even lower step frequencies, AMASS adapts and provides even better
|
||||||
// step smoothing. See stepper.c for more details on the AMASS system works.
|
// step smoothing. See stepper.c for more details on the AMASS system works.
|
||||||
#define ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING // Default enabled. Comment to disable.
|
#define ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING // Default enabled. Comment to disable.
|
||||||
|
|
||||||
// Sets the maximum step rate allowed to be written as a Grbl setting. This option enables an error
|
// Sets the maximum step rate allowed to be written as a Grbl setting. This option enables an error
|
||||||
// check in the settings module to prevent settings values that will exceed this limitation. The maximum
|
// check in the settings module to prevent settings values that will exceed this limitation. The maximum
|
||||||
// step rate is strictly limited by the CPU speed and will change if something other than an AVR running
|
// step rate is strictly limited by the CPU speed and will change if something other than an AVR running
|
||||||
// at 16MHz is used.
|
// at 16MHz is used.
|
||||||
@ -221,15 +313,15 @@
|
|||||||
// #define MAX_STEP_RATE_HZ 30000 // Hz
|
// #define MAX_STEP_RATE_HZ 30000 // Hz
|
||||||
|
|
||||||
// By default, Grbl sets all input pins to normal-high operation with their internal pull-up resistors
|
// By default, Grbl sets all input pins to normal-high operation with their internal pull-up resistors
|
||||||
// enabled. This simplifies the wiring for users by requiring only a switch connected to ground,
|
// enabled. This simplifies the wiring for users by requiring only a switch connected to ground,
|
||||||
// although its recommended that users take the extra step of wiring in low-pass filter to reduce
|
// although its recommended that users take the extra step of wiring in low-pass filter to reduce
|
||||||
// electrical noise detected by the pin. If the user inverts the pin in Grbl settings, this just flips
|
// electrical noise detected by the pin. If the user inverts the pin in Grbl settings, this just flips
|
||||||
// which high or low reading indicates an active signal. In normal operation, this means the user
|
// which high or low reading indicates an active signal. In normal operation, this means the user
|
||||||
// needs to connect a normal-open switch, but if inverted, this means the user should connect a
|
// needs to connect a normal-open switch, but if inverted, this means the user should connect a
|
||||||
// normal-closed switch.
|
// normal-closed switch.
|
||||||
// The following options disable the internal pull-up resistors, sets the pins to a normal-low
|
// The following options disable the internal pull-up resistors, sets the pins to a normal-low
|
||||||
// operation, and switches must be now connect to Vcc instead of ground. This also flips the meaning
|
// operation, and switches must be now connect to Vcc instead of ground. This also flips the meaning
|
||||||
// of the invert pin Grbl setting, where an inverted setting now means the user should connect a
|
// of the invert pin Grbl setting, where an inverted setting now means the user should connect a
|
||||||
// normal-open switch and vice versa.
|
// normal-open switch and vice versa.
|
||||||
// NOTE: All pins associated with the feature are disabled, i.e. XYZ limit pins, not individual axes.
|
// NOTE: All pins associated with the feature are disabled, i.e. XYZ limit pins, not individual axes.
|
||||||
// WARNING: When the pull-ups are disabled, this requires additional wiring with pull-down resistors!
|
// WARNING: When the pull-ups are disabled, this requires additional wiring with pull-down resistors!
|
||||||
@ -237,7 +329,7 @@
|
|||||||
//#define DISABLE_PROBE_PIN_PULL_UP
|
//#define DISABLE_PROBE_PIN_PULL_UP
|
||||||
//#define DISABLE_CONTROL_PIN_PULL_UP
|
//#define DISABLE_CONTROL_PIN_PULL_UP
|
||||||
|
|
||||||
// Sets which axis the tool length offset is applied. Assumes the spindle is always parallel with
|
// Sets which axis the tool length offset is applied. Assumes the spindle is always parallel with
|
||||||
// the selected axis with the tool oriented toward the negative direction. In other words, a positive
|
// the selected axis with the tool oriented toward the negative direction. In other words, a positive
|
||||||
// tool length offset value is subtracted from the current location.
|
// tool length offset value is subtracted from the current location.
|
||||||
#define TOOL_LENGTH_OFFSET_AXIS Z_AXIS // Default z-axis. Valid values are X_AXIS, Y_AXIS, or Z_AXIS.
|
#define TOOL_LENGTH_OFFSET_AXIS Z_AXIS // Default z-axis. Valid values are X_AXIS, Y_AXIS, or Z_AXIS.
|
||||||
@ -251,24 +343,24 @@
|
|||||||
// Used by variable spindle output only. This forces the PWM output to a minimum duty cycle when enabled.
|
// Used by variable spindle output only. This forces the PWM output to a minimum duty cycle when enabled.
|
||||||
// The PWM pin will still read 0V when the spindle is disabled. Most users will not need this option, but
|
// The PWM pin will still read 0V when the spindle is disabled. Most users will not need this option, but
|
||||||
// it may be useful in certain scenarios. This minimum PWM settings coincides with the spindle rpm minimum
|
// it may be useful in certain scenarios. This minimum PWM settings coincides with the spindle rpm minimum
|
||||||
// setting, like rpm max to max PWM. So the variable spindle pin will not output the voltage range between
|
// setting, like rpm max to max PWM. So the variable spindle pin will not output the voltage range between
|
||||||
// 0V for disabled and the voltage set by the minimum PWM for minimum rpm.
|
// 0V for disabled and the voltage set by the minimum PWM for minimum rpm.
|
||||||
// NOTE: Compute duty cycle at the minimum PWM by this equation: (% duty cycle)=(SPINDLE_MINIMUM_PWM/256)*100
|
// NOTE: Compute duty cycle at the minimum PWM by this equation: (% duty cycle)=(SPINDLE_MINIMUM_PWM/256)*100
|
||||||
// #define SPINDLE_MINIMUM_PWM 5 // Default disabled. Uncomment to enable. Integer (0-255)
|
// #define SPINDLE_MINIMUM_PWM 5 // Default disabled. Uncomment to enable. Integer (0-255)
|
||||||
|
|
||||||
// By default on a 328p(Uno), Grbl combines the variable spindle PWM and the enable into one pin to help
|
// By default on a 328p(Uno), Grbl combines the variable spindle PWM and the enable into one pin to help
|
||||||
// preserve I/O pins. For certain setups, these may need to be separate pins. This configure option uses
|
// preserve I/O pins. For certain setups, these may need to be separate pins. This configure option uses
|
||||||
// the spindle direction pin(D13) as a separate spindle enable pin along with spindle speed PWM on pin D11.
|
// the spindle direction pin(D13) as a separate spindle enable pin along with spindle speed PWM on pin D11.
|
||||||
// NOTE: This configure option only works with VARIABLE_SPINDLE enabled and a 328p processor (Uno).
|
// NOTE: This configure option only works with VARIABLE_SPINDLE enabled and a 328p processor (Uno).
|
||||||
// NOTE: With no direction pin, the spindle clockwise M4 g-code command will be removed. M3 and M5 still work.
|
// NOTE: With no direction pin, the spindle clockwise M4 g-code command will be removed. M3 and M5 still work.
|
||||||
// NOTE: BEWARE! The Arduino bootloader toggles the D13 pin when it powers up. If you flash Grbl with
|
// NOTE: BEWARE! The Arduino bootloader toggles the D13 pin when it powers up. If you flash Grbl with
|
||||||
// a programmer (you can use a spare Arduino as "Arduino as ISP". Search the web on how to wire this.),
|
// a programmer (you can use a spare Arduino as "Arduino as ISP". Search the web on how to wire this.),
|
||||||
// this D13 LED toggling should go away. We haven't tested this though. Please report how it goes!
|
// this D13 LED toggling should go away. We haven't tested this though. Please report how it goes!
|
||||||
// #define USE_SPINDLE_DIR_AS_ENABLE_PIN // Default disabled. Uncomment to enable.
|
// #define USE_SPINDLE_DIR_AS_ENABLE_PIN // Default disabled. Uncomment to enable.
|
||||||
|
|
||||||
// With this enabled, Grbl sends back an echo of the line it has received, which has been pre-parsed (spaces
|
// With this enabled, Grbl sends back an echo of the line it has received, which has been pre-parsed (spaces
|
||||||
// removed, capitalized letters, no comments) and is to be immediately executed by Grbl. Echoes will not be
|
// removed, capitalized letters, no comments) and is to be immediately executed by Grbl. Echoes will not be
|
||||||
// sent upon a line buffer overflow, but should for all normal lines sent to Grbl. For example, if a user
|
// sent upon a line buffer overflow, but should for all normal lines sent to Grbl. For example, if a user
|
||||||
// sendss the line 'g1 x1.032 y2.45 (test comment)', Grbl will echo back in the form '[echo: G1X1.032Y2.45]'.
|
// sendss the line 'g1 x1.032 y2.45 (test comment)', Grbl will echo back in the form '[echo: G1X1.032Y2.45]'.
|
||||||
// NOTE: Only use this for debugging purposes!! When echoing, this takes up valuable resources and can effect
|
// NOTE: Only use this for debugging purposes!! When echoing, this takes up valuable resources and can effect
|
||||||
// performance. If absolutely needed for normal operation, the serial write buffer should be greatly increased
|
// performance. If absolutely needed for normal operation, the serial write buffer should be greatly increased
|
||||||
@ -289,15 +381,15 @@
|
|||||||
// machines, perhaps to 0.1mm/min, but your success may vary based on multiple factors.
|
// machines, perhaps to 0.1mm/min, but your success may vary based on multiple factors.
|
||||||
#define MINIMUM_FEED_RATE 1.0 // (mm/min)
|
#define MINIMUM_FEED_RATE 1.0 // (mm/min)
|
||||||
|
|
||||||
// Number of arc generation iterations by small angle approximation before exact arc trajectory
|
// Number of arc generation iterations by small angle approximation before exact arc trajectory
|
||||||
// correction with expensive sin() and cos() calcualtions. This parameter maybe decreased if there
|
// correction with expensive sin() and cos() calcualtions. This parameter maybe decreased if there
|
||||||
// are issues with the accuracy of the arc generations, or increased if arc execution is getting
|
// are issues with the accuracy of the arc generations, or increased if arc execution is getting
|
||||||
// bogged down by too many trig calculations.
|
// bogged down by too many trig calculations.
|
||||||
#define N_ARC_CORRECTION 12 // Integer (1-255)
|
#define N_ARC_CORRECTION 12 // Integer (1-255)
|
||||||
|
|
||||||
// The arc G2/3 g-code standard is problematic by definition. Radius-based arcs have horrible numerical
|
// The arc G2/3 g-code standard is problematic by definition. Radius-based arcs have horrible numerical
|
||||||
// errors when arc at semi-circles(pi) or full-circles(2*pi). Offset-based arcs are much more accurate
|
// errors when arc at semi-circles(pi) or full-circles(2*pi). Offset-based arcs are much more accurate
|
||||||
// but still have a problem when arcs are full-circles (2*pi). This define accounts for the floating
|
// but still have a problem when arcs are full-circles (2*pi). This define accounts for the floating
|
||||||
// point issues when offset-based arcs are commanded as full circles, but get interpreted as extremely
|
// point issues when offset-based arcs are commanded as full circles, but get interpreted as extremely
|
||||||
// small arcs with around machine epsilon (1.2e-7rad) due to numerical round-off and precision issues.
|
// small arcs with around machine epsilon (1.2e-7rad) due to numerical round-off and precision issues.
|
||||||
// This define value sets the machine epsilon cutoff to determine if the arc is a full-circle or not.
|
// This define value sets the machine epsilon cutoff to determine if the arc is a full-circle or not.
|
||||||
@ -307,16 +399,16 @@
|
|||||||
|
|
||||||
// Time delay increments performed during a dwell. The default value is set at 50ms, which provides
|
// Time delay increments performed during a dwell. The default value is set at 50ms, which provides
|
||||||
// a maximum time delay of roughly 55 minutes, more than enough for most any application. Increasing
|
// a maximum time delay of roughly 55 minutes, more than enough for most any application. Increasing
|
||||||
// this delay will increase the maximum dwell time linearly, but also reduces the responsiveness of
|
// this delay will increase the maximum dwell time linearly, but also reduces the responsiveness of
|
||||||
// run-time command executions, like status reports, since these are performed between each dwell
|
// run-time command executions, like status reports, since these are performed between each dwell
|
||||||
// time step. Also, keep in mind that the Arduino delay timer is not very accurate for long delays.
|
// time step. Also, keep in mind that the Arduino delay timer is not very accurate for long delays.
|
||||||
#define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds)
|
#define DWELL_TIME_STEP 50 // Integer (1-255) (milliseconds)
|
||||||
|
|
||||||
// Creates a delay between the direction pin setting and corresponding step pulse by creating
|
// Creates a delay between the direction pin setting and corresponding step pulse by creating
|
||||||
// another interrupt (Timer2 compare) to manage it. The main Grbl interrupt (Timer1 compare)
|
// another interrupt (Timer2 compare) to manage it. The main Grbl interrupt (Timer1 compare)
|
||||||
// sets the direction pins, and does not immediately set the stepper pins, as it would in
|
// sets the direction pins, and does not immediately set the stepper pins, as it would in
|
||||||
// normal operation. The Timer2 compare fires next to set the stepper pins after the step
|
// normal operation. The Timer2 compare fires next to set the stepper pins after the step
|
||||||
// pulse delay time, and Timer2 overflow will complete the step pulse, except now delayed
|
// pulse delay time, and Timer2 overflow will complete the step pulse, except now delayed
|
||||||
// by the step pulse time plus the step pulse delay. (Thanks langwadt for the idea!)
|
// by the step pulse time plus the step pulse delay. (Thanks langwadt for the idea!)
|
||||||
// NOTE: Uncomment to enable. The recommended delay must be > 3us, and, when added with the
|
// NOTE: Uncomment to enable. The recommended delay must be > 3us, and, when added with the
|
||||||
// user-supplied step pulse time, the total time must not exceed 127us. Reported successful
|
// user-supplied step pulse time, the total time must not exceed 127us. Reported successful
|
||||||
@ -324,62 +416,50 @@
|
|||||||
// #define STEP_PULSE_DELAY 10 // Step pulse delay in microseconds. Default disabled.
|
// #define STEP_PULSE_DELAY 10 // Step pulse delay in microseconds. Default disabled.
|
||||||
|
|
||||||
// The number of linear motions in the planner buffer to be planned at any give time. The vast
|
// The number of linear motions in the planner buffer to be planned at any give time. The vast
|
||||||
// majority of RAM that Grbl uses is based on this buffer size. Only increase if there is extra
|
// majority of RAM that Grbl uses is based on this buffer size. Only increase if there is extra
|
||||||
// available RAM, like when re-compiling for a Mega or Sanguino. Or decrease if the Arduino
|
// available RAM, like when re-compiling for a Mega2560. Or decrease if the Arduino begins to
|
||||||
// begins to crash due to the lack of available RAM or if the CPU is having trouble keeping
|
// crash due to the lack of available RAM or if the CPU is having trouble keeping up with planning
|
||||||
// up with planning new incoming motions as they are executed.
|
// new incoming motions as they are executed.
|
||||||
// #define BLOCK_BUFFER_SIZE 18 // Uncomment to override default in planner.h.
|
// #define BLOCK_BUFFER_SIZE 17 // Uncomment to override default in planner.h.
|
||||||
|
|
||||||
// Governs the size of the intermediary step segment buffer between the step execution algorithm
|
// Governs the size of the intermediary step segment buffer between the step execution algorithm
|
||||||
// and the planner blocks. Each segment is set of steps executed at a constant velocity over a
|
// and the planner blocks. Each segment is set of steps executed at a constant velocity over a
|
||||||
// fixed time defined by ACCELERATION_TICKS_PER_SECOND. They are computed such that the planner
|
// fixed time defined by ACCELERATION_TICKS_PER_SECOND. They are computed such that the planner
|
||||||
// block velocity profile is traced exactly. The size of this buffer governs how much step
|
// block velocity profile is traced exactly. The size of this buffer governs how much step
|
||||||
// execution lead time there is for other Grbl processes have to compute and do their thing
|
// execution lead time there is for other Grbl processes have to compute and do their thing
|
||||||
// before having to come back and refill this buffer, currently at ~50msec of step moves.
|
// before having to come back and refill this buffer, currently at ~50msec of step moves.
|
||||||
// #define SEGMENT_BUFFER_SIZE 6 // Uncomment to override default in stepper.h.
|
// #define SEGMENT_BUFFER_SIZE 6 // Uncomment to override default in stepper.h.
|
||||||
|
|
||||||
// Line buffer size from the serial input stream to be executed. Also, governs the size of
|
// Line buffer size from the serial input stream to be executed. Also, governs the size of
|
||||||
// each of the startup blocks, as they are each stored as a string of this size. Make sure
|
// each of the startup blocks, as they are each stored as a string of this size. Make sure
|
||||||
// to account for the available EEPROM at the defined memory address in settings.h and for
|
// to account for the available EEPROM at the defined memory address in settings.h and for
|
||||||
// the number of desired startup blocks.
|
// the number of desired startup blocks.
|
||||||
// NOTE: 80 characters is not a problem except for extreme cases, but the line buffer size
|
// NOTE: 80 characters is not a problem except for extreme cases, but the line buffer size
|
||||||
// can be too small and g-code blocks can get truncated. Officially, the g-code standards
|
// can be too small and g-code blocks can get truncated. Officially, the g-code standards
|
||||||
// support up to 256 characters. In future versions, this default will be increased, when
|
// support up to 256 characters. In future versions, this default will be increased, when
|
||||||
// we know how much extra memory space we can re-invest into this.
|
// we know how much extra memory space we can re-invest into this.
|
||||||
// #define LINE_BUFFER_SIZE 80 // Uncomment to override default in protocol.h
|
// #define LINE_BUFFER_SIZE 80 // Uncomment to override default in protocol.h
|
||||||
|
|
||||||
// Serial send and receive buffer size. The receive buffer is often used as another streaming
|
// Serial send and receive buffer size. The receive buffer is often used as another streaming
|
||||||
// buffer to store incoming blocks to be processed by Grbl when its ready. Most streaming
|
// buffer to store incoming blocks to be processed by Grbl when its ready. Most streaming
|
||||||
// interfaces will character count and track each block send to each block response. So,
|
// interfaces will character count and track each block send to each block response. So,
|
||||||
// increase the receive buffer if a deeper receive buffer is needed for streaming and avaiable
|
// increase the receive buffer if a deeper receive buffer is needed for streaming and avaiable
|
||||||
// memory allows. The send buffer primarily handles messages in Grbl. Only increase if large
|
// memory allows. The send buffer primarily handles messages in Grbl. Only increase if large
|
||||||
// messages are sent and Grbl begins to stall, waiting to send the rest of the message.
|
// messages are sent and Grbl begins to stall, waiting to send the rest of the message.
|
||||||
// NOTE: Buffer size values must be greater than zero and less than 256.
|
// NOTE: Grbl generates an average status report in about 0.5msec, but the serial TX stream at
|
||||||
// #define RX_BUFFER_SIZE 128 // Uncomment to override defaults in serial.h
|
// 115200 baud will take 5 msec to transmit a typical 55 character report. Worst case reports are
|
||||||
// #define TX_BUFFER_SIZE 64
|
// around 90-100 characters. As long as the serial TX buffer doesn't get continually maxed, Grbl
|
||||||
|
// will continue operating efficiently. Size the TX buffer around the size of a worst-case report.
|
||||||
// Toggles XON/XOFF software flow control for serial communications. Not officially supported
|
// #define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h
|
||||||
// due to problems involving the Atmega8U2 USB-to-serial chips on current Arduinos. The firmware
|
// #define TX_BUFFER_SIZE 90 // (1-254)
|
||||||
// on these chips do not support XON/XOFF flow control characters and the intermediate buffer
|
|
||||||
// in the chips cause latency and overflow problems with standard terminal programs. However,
|
|
||||||
// using specifically-programmed UI's to manage this latency problem has been confirmed to work.
|
|
||||||
// As well as, older FTDI FT232RL-based Arduinos(Duemilanove) are known to work with standard
|
|
||||||
// terminal programs since their firmware correctly manage these XON/XOFF characters. In any
|
|
||||||
// case, please report any successes to grbl administrators!
|
|
||||||
// #define ENABLE_XONXOFF // Default disabled. Uncomment to enable.
|
|
||||||
|
|
||||||
// A simple software debouncing feature for hard limit switches. When enabled, the interrupt
|
// Configures the position after a probing cycle during Grbl's check mode. Disabled sets
|
||||||
// monitoring the hard limit switch pins will enable the Arduino's watchdog timer to re-check
|
// the position to the probe target, when enabled sets the position to the start position.
|
||||||
// the limit pin state after a delay of about 32msec. This can help with CNC machines with
|
// #define SET_CHECK_MODE_PROBE_TO_START // Default disabled. Uncomment to enable.
|
||||||
// problematic false triggering of their hard limit switches, but it WILL NOT fix issues with
|
|
||||||
// electrical interference on the signal cables from external sources. It's recommended to first
|
|
||||||
// use shielded signal cables with their shielding connected to ground (old USB/computer cables
|
|
||||||
// work well and are cheap to find) and wire in a low-pass circuit into each limit pin.
|
|
||||||
// #define ENABLE_SOFTWARE_DEBOUNCE // Default disabled. Uncomment to enable.
|
|
||||||
|
|
||||||
// Force Grbl to check the state of the hard limit switches when the processor detects a pin
|
// Force Grbl to check the state of the hard limit switches when the processor detects a pin
|
||||||
// change inside the hard limit ISR routine. By default, Grbl will trigger the hard limits
|
// change inside the hard limit ISR routine. By default, Grbl will trigger the hard limits
|
||||||
// alarm upon any pin change, since bouncing switches can cause a state check like this to
|
// alarm upon any pin change, since bouncing switches can cause a state check like this to
|
||||||
// misread the pin. When hard limits are triggered, they should be 100% reliable, which is the
|
// misread the pin. When hard limits are triggered, they should be 100% reliable, which is the
|
||||||
// reason that this option is disabled by default. Only if your system/electronics can guarantee
|
// reason that this option is disabled by default. Only if your system/electronics can guarantee
|
||||||
// that the switches don't bounce, we recommend enabling this option. This will help prevent
|
// that the switches don't bounce, we recommend enabling this option. This will help prevent
|
||||||
@ -388,7 +468,7 @@
|
|||||||
// #define HARD_LIMIT_FORCE_STATE_CHECK // Default disabled. Uncomment to enable.
|
// #define HARD_LIMIT_FORCE_STATE_CHECK // Default disabled. Uncomment to enable.
|
||||||
|
|
||||||
// Adjusts homing cycle search and locate scalars. These are the multipliers used by Grbl's
|
// Adjusts homing cycle search and locate scalars. These are the multipliers used by Grbl's
|
||||||
// homing cycle to ensure the limit switches are engaged and cleared through each phase of
|
// homing cycle to ensure the limit switches are engaged and cleared through each phase of
|
||||||
// the cycle. The search phase uses the axes max-travel setting times the SEARCH_SCALAR to
|
// the cycle. The search phase uses the axes max-travel setting times the SEARCH_SCALAR to
|
||||||
// determine distance to look for the limit switch. Once found, the locate phase begins and
|
// determine distance to look for the limit switch. Once found, the locate phase begins and
|
||||||
// uses the homing pull-off distance setting times the LOCATE_SCALAR to pull-off and re-engage
|
// uses the homing pull-off distance setting times the LOCATE_SCALAR to pull-off and re-engage
|
||||||
@ -397,27 +477,70 @@
|
|||||||
// #define HOMING_AXIS_SEARCH_SCALAR 1.5 // Uncomment to override defaults in limits.c.
|
// #define HOMING_AXIS_SEARCH_SCALAR 1.5 // Uncomment to override defaults in limits.c.
|
||||||
// #define HOMING_AXIS_LOCATE_SCALAR 10.0 // Uncomment to override defaults in limits.c.
|
// #define HOMING_AXIS_LOCATE_SCALAR 10.0 // Uncomment to override defaults in limits.c.
|
||||||
|
|
||||||
|
// Enable the '$RST=*', '$RST=$', and '$RST=#' eeprom restore commands. There are cases where
|
||||||
|
// these commands may be undesirable. Simply comment the desired macro to disable it.
|
||||||
|
// NOTE: See SETTINGS_RESTORE_ALL macro for customizing the `$RST=*` command.
|
||||||
|
#define ENABLE_RESTORE_EEPROM_WIPE_ALL // '$RST=*' Default enabled. Comment to disable.
|
||||||
|
#define ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // '$RST=$' Default enabled. Comment to disable.
|
||||||
|
#define ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // '$RST=#' Default enabled. Comment to disable.
|
||||||
|
|
||||||
|
// Defines the EEPROM data restored upon a settings version change and `$RST=*` command. Whenever the
|
||||||
|
// the settings or other EEPROM data structure changes between Grbl versions, Grbl will automatically
|
||||||
|
// wipe and restore the EEPROM. This macro controls what data is wiped and restored. This is useful
|
||||||
|
// particularily for OEMs that need to retain certain data. For example, the BUILD_INFO string can be
|
||||||
|
// written into the Arduino EEPROM via a seperate .INO sketch to contain product data. Altering this
|
||||||
|
// macro to not restore the build info EEPROM will ensure this data is retained after firmware upgrades.
|
||||||
|
// NOTE: Uncomment to override defaults in settings.h
|
||||||
|
// #define SETTINGS_RESTORE_ALL (SETTINGS_RESTORE_DEFAULTS | SETTINGS_RESTORE_PARAMETERS | SETTINGS_RESTORE_STARTUP_LINES | SETTINGS_RESTORE_BUILD_INFO)
|
||||||
|
|
||||||
|
// Enable the '$I=(string)' build info write command. If disabled, any existing build info data must
|
||||||
|
// be placed into EEPROM via external means with a valid checksum value. This macro option is useful
|
||||||
|
// to prevent this data from being over-written by a user, when used to store OEM product data.
|
||||||
|
// NOTE: See the included grblWrite_BuildInfo.ino example file to write this string seperately.
|
||||||
|
#define ENABLE_BUILD_INFO_WRITE_COMMAND // '$I=' Default enabled. Comment to disable.
|
||||||
|
|
||||||
|
// AVR processors require all interrupts to be disabled during an EEPROM write. This includes both
|
||||||
|
// the stepper ISRs and serial comm ISRs. In the event of a long EEPROM write, this ISR pause can
|
||||||
|
// cause active stepping to lose position and serial receive data to be lost. This configuration
|
||||||
|
// option forces the planner buffer to completely empty whenever the EEPROM is written to prevent
|
||||||
|
// any chance of lost steps.
|
||||||
|
// However, this doesn't prevent issues with lost serial RX data during an EEPROM write, especially
|
||||||
|
// if a GUI is premptively filling up the serial RX buffer simultaneously. It's highly advised for
|
||||||
|
// GUIs to flag these gcodes (G10,G28.1,G30.1) to always wait for an 'ok' after a block containing
|
||||||
|
// one of these commands before sending more data to eliminate this issue.
|
||||||
|
// NOTE: Most EEPROM write commands are implicitly blocked during a job (all '$' commands). However,
|
||||||
|
// coordinate set g-code commands (G10,G28/30.1) are not, since they are part of an active streaming
|
||||||
|
// job. At this time, this option only forces a planner buffer sync with these g-code commands.
|
||||||
|
#define FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // Default enabled. Comment to disable.
|
||||||
|
|
||||||
|
// 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. This option forces the planner buffer to empty, sync, and stop
|
||||||
|
// 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.
|
||||||
|
#define FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // Default enabled. Comment to disable.
|
||||||
|
|
||||||
// Enables and configures parking motion methods upon a safety door state. Primarily for OEMs
|
// Enables and configures parking motion methods upon a safety door state. Primarily for OEMs
|
||||||
// that desire this feature for their integrated machines. At the moment, Grbl assumes that
|
// that desire this feature for their integrated machines. At the moment, Grbl assumes that
|
||||||
// the parking motion only involves one axis, although the parking implementation was written
|
// the parking motion only involves one axis, although the parking implementation was written
|
||||||
// to be easily refactored for any number of motions on different axes by altering the parking
|
// to be easily refactored for any number of motions on different axes by altering the parking
|
||||||
// source code. At this time, Grbl only supports parking one axis (typically the Z-axis) that
|
// source code. At this time, Grbl only supports parking one axis (typically the Z-axis) that
|
||||||
// moves in the positive direction upon retracting and negative direction upon restoring position.
|
// moves in the positive direction upon retracting and negative direction upon restoring position.
|
||||||
// The motion executes with a slow pull-out retraction motion, power-down, and a fast park.
|
// The motion executes with a slow pull-out retraction motion, power-down, and a fast park.
|
||||||
// Restoring to the resume position follows these set motions in reverse: fast restore to
|
// Restoring to the resume position follows these set motions in reverse: fast restore to
|
||||||
// pull-out position, power-up with a time-out, and plunge back to the original position at the
|
// pull-out position, power-up with a time-out, and plunge back to the original position at the
|
||||||
// slower pull-out rate.
|
// slower pull-out rate.
|
||||||
// NOTE: Still a work-in-progress. Machine coordinates must be in all negative space and
|
// NOTE: Still a work-in-progress. Machine coordinates must be in all negative space and
|
||||||
// does not work with HOMING_FORCE_SET_ORIGIN enabled. Parking motion also moves only in
|
// does not work with HOMING_FORCE_SET_ORIGIN enabled. Parking motion also moves only in
|
||||||
// positive direction.
|
// positive direction.
|
||||||
// #define PARKING_ENABLE // Default disabled. Uncomment to enable
|
// #define PARKING_ENABLE // Default disabled. Uncomment to enable
|
||||||
|
|
||||||
// Configure options for the parking motion, if enabled.
|
// Configure options for the parking motion, if enabled.
|
||||||
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
|
#define PARKING_AXIS Z_AXIS // Define which axis that performs the parking motion
|
||||||
#define PARKING_TARGET -5.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
|
#define PARKING_TARGET -5.0 // Parking axis target. In mm, as machine coordinate [-max_travel,0].
|
||||||
#define PARKING_RATE -1.0 // Parking fast rate after pull-out. In mm/min or (-1.0) for seek rate.
|
#define PARKING_RATE 500.0 // Parking fast rate after pull-out in mm/min.
|
||||||
#define PARKING_PULLOUT_RATE 250.0 // Pull-out/plunge slow feed rate in mm/min.
|
#define PARKING_PULLOUT_RATE 100.0 // Pull-out/plunge slow feed rate in mm/min.
|
||||||
#define PARKING_PULLOUT_INCREMENT 5.0 // Spindle pull-out and plunge distance in mm. Incremental distance.
|
#define PARKING_PULLOUT_INCREMENT 5.0 // Spindle pull-out and plunge distance in mm. Incremental distance.
|
||||||
// Must be positive value or equal to zero.
|
// Must be positive value or equal to zero.
|
||||||
|
|
||||||
@ -445,7 +568,7 @@
|
|||||||
|
|
||||||
/* ---------------------------------------------------------------------------------------
|
/* ---------------------------------------------------------------------------------------
|
||||||
OEM Single File Configuration Option
|
OEM Single File Configuration Option
|
||||||
|
|
||||||
Instructions: Paste the cpu_map and default setting definitions below without an enclosing
|
Instructions: Paste the cpu_map and default setting definitions below without an enclosing
|
||||||
#ifdef. Comment out the CPU_MAP_xxx and DEFAULT_xxx defines at the top of this file, and
|
#ifdef. Comment out the CPU_MAP_xxx and DEFAULT_xxx defines at the top of this file, and
|
||||||
the compiler will ignore the contents of defaults.h and cpu_map.h and use the definitions
|
the compiler will ignore the contents of defaults.h and cpu_map.h and use the definitions
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
coolant_control.c - coolant control methods
|
coolant_control.c - coolant control methods
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -16,51 +16,58 @@
|
|||||||
|
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
|
|
||||||
|
|
||||||
void coolant_init()
|
void coolant_init()
|
||||||
{
|
{
|
||||||
COOLANT_FLOOD_DDR |= (1 << COOLANT_FLOOD_BIT);
|
COOLANT_FLOOD_DDR |= (1 << COOLANT_FLOOD_BIT); // Configure as output pin
|
||||||
#ifdef ENABLE_M7
|
#ifdef ENABLE_M7
|
||||||
COOLANT_MIST_DDR |= (1 << COOLANT_MIST_BIT);
|
COOLANT_MIST_DDR |= (1 << COOLANT_MIST_BIT);
|
||||||
#endif
|
#endif
|
||||||
coolant_stop();
|
coolant_set_state(COOLANT_DISABLE);
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void coolant_stop()
|
|
||||||
{
|
|
||||||
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
|
|
||||||
#ifdef ENABLE_M7
|
|
||||||
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void coolant_set_state(uint8_t mode)
|
void coolant_set_state(uint8_t mode)
|
||||||
{
|
{
|
||||||
if (sys.abort) { return; } // Block during abort.
|
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||||
|
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||||
if (mode == COOLANT_FLOOD_ENABLE) {
|
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
|
||||||
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
|
#else
|
||||||
|
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
|
||||||
#ifdef ENABLE_M7
|
#endif
|
||||||
} else if (mode == COOLANT_MIST_ENABLE) {
|
|
||||||
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
coolant_stop();
|
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||||
|
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
|
||||||
|
#else
|
||||||
|
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
#ifdef ENABLE_M7
|
||||||
|
if (mode & COOLANT_MIST_ENABLE) {
|
||||||
|
#ifdef INVERT_COOLANT_MIST_PIN
|
||||||
|
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
|
||||||
|
#else
|
||||||
|
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
|
||||||
|
#endif
|
||||||
|
} else {
|
||||||
|
#ifdef INVERT_COOLANT_MIST_PIN
|
||||||
|
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
|
||||||
|
#else
|
||||||
|
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void coolant_run(uint8_t mode)
|
void coolant_run(uint8_t mode)
|
||||||
{
|
{
|
||||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||||
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
||||||
|
if (sys.abort) { return; } // Block during abort.
|
||||||
coolant_set_state(mode);
|
coolant_set_state(mode);
|
||||||
}
|
}
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
coolant_control.h - spindle control methods
|
coolant_control.h - spindle control methods
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -19,12 +19,11 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef coolant_control_h
|
#ifndef coolant_control_h
|
||||||
#define coolant_control_h
|
#define coolant_control_h
|
||||||
|
|
||||||
|
|
||||||
void coolant_init();
|
void coolant_init();
|
||||||
void coolant_stop();
|
|
||||||
void coolant_set_state(uint8_t mode);
|
void coolant_set_state(uint8_t mode);
|
||||||
void coolant_run(uint8_t mode);
|
void coolant_run(uint8_t mode);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
cpu_map.h - CPU and pin mapping configuration file
|
cpu_map.h - CPU and pin mapping configuration file
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -18,7 +18,7 @@
|
|||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
/* The cpu_map.h files serve as a central pin mapping selection file for different
|
/* The cpu_map.h files serve as a central pin mapping selection file for different
|
||||||
processor types or alternative pin layouts. This version of Grbl officially supports
|
processor types or alternative pin layouts. This version of Grbl officially supports
|
||||||
only the Arduino Mega328p. */
|
only the Arduino Mega328p. */
|
||||||
|
|
||||||
@ -55,28 +55,28 @@
|
|||||||
#define STEPPERS_DISABLE_BIT 0 // Uno Digital Pin 8
|
#define STEPPERS_DISABLE_BIT 0 // Uno Digital Pin 8
|
||||||
#define STEPPERS_DISABLE_MASK (1<<STEPPERS_DISABLE_BIT)
|
#define STEPPERS_DISABLE_MASK (1<<STEPPERS_DISABLE_BIT)
|
||||||
|
|
||||||
// Define homing/hard limit switch input pins and limit interrupt vectors.
|
// Define homing/hard limit switch input pins and limit interrupt vectors.
|
||||||
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
|
// NOTE: All limit bit pins must be on the same port, but not on a port with other input pins (CONTROL).
|
||||||
#define LIMIT_DDR DDRB
|
#define LIMIT_DDR DDRB
|
||||||
#define LIMIT_PIN PINB
|
#define LIMIT_PIN PINB
|
||||||
#define LIMIT_PORT PORTB
|
#define LIMIT_PORT PORTB
|
||||||
#define X_LIMIT_BIT 1 // Uno Digital Pin 9
|
#define X_LIMIT_BIT 1 // Uno Digital Pin 9
|
||||||
#define Y_LIMIT_BIT 2 // Uno Digital Pin 10
|
#define Y_LIMIT_BIT 2 // Uno Digital Pin 10
|
||||||
#ifdef VARIABLE_SPINDLE // Z Limit pin and spindle enabled swapped to access hardware PWM on Pin 11.
|
#ifdef VARIABLE_SPINDLE // Z Limit pin and spindle enabled swapped to access hardware PWM on Pin 11.
|
||||||
#define Z_LIMIT_BIT 4 // Uno Digital Pin 12
|
#define Z_LIMIT_BIT 4 // Uno Digital Pin 12
|
||||||
#else
|
#else
|
||||||
#define Z_LIMIT_BIT 3 // Uno Digital Pin 11
|
#define Z_LIMIT_BIT 3 // Uno Digital Pin 11
|
||||||
#endif
|
#endif
|
||||||
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)) // All limit bits
|
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)) // All limit bits
|
||||||
#define LIMIT_INT PCIE0 // Pin change interrupt enable pin
|
#define LIMIT_INT PCIE0 // Pin change interrupt enable pin
|
||||||
#define LIMIT_INT_vect PCINT0_vect
|
#define LIMIT_INT_vect PCINT0_vect
|
||||||
#define LIMIT_PCMSK PCMSK0 // Pin change interrupt register
|
#define LIMIT_PCMSK PCMSK0 // Pin change interrupt register
|
||||||
|
|
||||||
// Define spindle enable and spindle direction output pins.
|
// Define spindle enable and spindle direction output pins.
|
||||||
#define SPINDLE_ENABLE_DDR DDRB
|
#define SPINDLE_ENABLE_DDR DDRB
|
||||||
#define SPINDLE_ENABLE_PORT PORTB
|
#define SPINDLE_ENABLE_PORT PORTB
|
||||||
// Z Limit pin and spindle PWM/enable pin swapped to access hardware PWM on Pin 11.
|
// Z Limit pin and spindle PWM/enable pin swapped to access hardware PWM on Pin 11.
|
||||||
#ifdef VARIABLE_SPINDLE
|
#ifdef VARIABLE_SPINDLE
|
||||||
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||||
// If enabled, spindle direction pin now used as spindle enable, while PWM remains on D11.
|
// If enabled, spindle direction pin now used as spindle enable, while PWM remains on D11.
|
||||||
#define SPINDLE_ENABLE_BIT 5 // Uno Digital Pin 13 (NOTE: D13 can't be pulled-high input due to LED.)
|
#define SPINDLE_ENABLE_BIT 5 // Uno Digital Pin 13 (NOTE: D13 can't be pulled-high input due to LED.)
|
||||||
@ -91,18 +91,14 @@
|
|||||||
#define SPINDLE_DIRECTION_PORT PORTB
|
#define SPINDLE_DIRECTION_PORT PORTB
|
||||||
#define SPINDLE_DIRECTION_BIT 5 // Uno Digital Pin 13 (NOTE: D13 can't be pulled-high input due to LED.)
|
#define SPINDLE_DIRECTION_BIT 5 // Uno Digital Pin 13 (NOTE: D13 can't be pulled-high input due to LED.)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Define flood and mist coolant enable output pins.
|
// Define flood and mist coolant enable output pins.
|
||||||
// NOTE: Uno analog pins 4 and 5 are reserved for an i2c interface, and may be installed at
|
|
||||||
// a later date if flash and memory space allows.
|
|
||||||
#define COOLANT_FLOOD_DDR DDRC
|
#define COOLANT_FLOOD_DDR DDRC
|
||||||
#define COOLANT_FLOOD_PORT PORTC
|
#define COOLANT_FLOOD_PORT PORTC
|
||||||
#define COOLANT_FLOOD_BIT 3 // Uno Analog Pin 3
|
#define COOLANT_FLOOD_BIT 3 // Uno Analog Pin 3
|
||||||
#ifdef ENABLE_M7 // Mist coolant disabled by default. See config.h to enable/disable.
|
#define COOLANT_MIST_DDR DDRC
|
||||||
#define COOLANT_MIST_DDR DDRC
|
#define COOLANT_MIST_PORT PORTC
|
||||||
#define COOLANT_MIST_PORT PORTC
|
#define COOLANT_MIST_BIT 4 // Uno Analog Pin 3
|
||||||
#define COOLANT_MIST_BIT 4 // Uno Analog Pin 4
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Define user-control controls (cycle start, reset, feed hold) input pins.
|
// Define user-control controls (cycle start, reset, feed hold) input pins.
|
||||||
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
|
// NOTE: All CONTROLs pins must be on the same port and not on a port with other input pins (limits).
|
||||||
@ -118,7 +114,7 @@
|
|||||||
#define CONTROL_PCMSK PCMSK1 // Pin change interrupt register
|
#define CONTROL_PCMSK PCMSK1 // Pin change interrupt register
|
||||||
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
|
#define CONTROL_MASK ((1<<CONTROL_RESET_BIT)|(1<<CONTROL_FEED_HOLD_BIT)|(1<<CONTROL_CYCLE_START_BIT)|(1<<CONTROL_SAFETY_DOOR_BIT))
|
||||||
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
|
#define CONTROL_INVERT_MASK CONTROL_MASK // May be re-defined to only invert certain control pins.
|
||||||
|
|
||||||
// Define probe switch input pin.
|
// Define probe switch input pin.
|
||||||
#define PROBE_DDR DDRC
|
#define PROBE_DDR DDRC
|
||||||
#define PROBE_PIN PINC
|
#define PROBE_PIN PINC
|
||||||
@ -126,28 +122,30 @@
|
|||||||
#define PROBE_BIT 5 // Uno Analog Pin 5
|
#define PROBE_BIT 5 // Uno Analog Pin 5
|
||||||
#define PROBE_MASK (1<<PROBE_BIT)
|
#define PROBE_MASK (1<<PROBE_BIT)
|
||||||
|
|
||||||
// Start of PWM & Stepper Enabled Spindle
|
// Variable spindle configuration below. Do not change unless you know what you are doing.
|
||||||
#ifdef VARIABLE_SPINDLE
|
// NOTE: Only used when variable spindle is enabled.
|
||||||
// Advanced Configuration Below You should not need to touch these variables
|
#define SPINDLE_PWM_MAX_VALUE 255.0 // Don't change. 328p fast PWM mode fixes top value as 255.
|
||||||
#define SPINDLE_PWM_MAX_VALUE 255.0 // Don't change. 328p fast PWM mode fixes top value as 255.
|
#define SPINDLE_PWM_OFF_VALUE 0.0
|
||||||
#define SPINDLE_TCCRA_REGISTER TCCR2A
|
#define SPINDLE_TCCRA_REGISTER TCCR2A
|
||||||
#define SPINDLE_TCCRB_REGISTER TCCR2B
|
#define SPINDLE_TCCRB_REGISTER TCCR2B
|
||||||
#define SPINDLE_OCR_REGISTER OCR2A
|
#define SPINDLE_OCR_REGISTER OCR2A
|
||||||
#define SPINDLE_COMB_BIT COM2A1
|
#define SPINDLE_COMB_BIT COM2A1
|
||||||
|
|
||||||
// 1/8 Prescaler, 8-bit Fast PWM mode. Translates to about 7.8kHz PWM frequency.
|
// Prescaled, 8-bit Fast PWM mode.
|
||||||
#define SPINDLE_TCCRA_INIT_MASK ((1<<WGM20) | (1<<WGM21))
|
#define SPINDLE_TCCRA_INIT_MASK ((1<<WGM20) | (1<<WGM21)) // Configures fast PWM mode.
|
||||||
#define SPINDLE_TCCRB_INIT_MASK (1<<CS21)
|
// #define SPINDLE_TCCRB_INIT_MASK (1<<CS21) // 1/8 prescaler -> 7.8kHz (Used in v0.9)
|
||||||
|
// #define SPINDLE_TCCRB_INIT_MASK ((1<<CS21) | (1<<CS20)) // 1/32 prescaler -> 1.96kHz
|
||||||
// NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings.
|
#define SPINDLE_TCCRB_INIT_MASK (1<<CS22) // 1/64 prescaler -> 0.98kHz
|
||||||
#define SPINDLE_PWM_DDR DDRB
|
|
||||||
#define SPINDLE_PWM_PORT PORTB
|
|
||||||
#define SPINDLE_PWM_BIT 3 // Uno Digital Pin 11
|
// NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings.
|
||||||
#endif // End of VARIABLE_SPINDLE
|
#define SPINDLE_PWM_DDR DDRB
|
||||||
|
#define SPINDLE_PWM_PORT PORTB
|
||||||
|
#define SPINDLE_PWM_BIT 3 // Uno Digital Pin 11
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
#ifdef CPU_MAP_CUSTOM_PROC
|
#ifdef CPU_MAP_CUSTOM_PROC
|
||||||
// For a custom pin map or different processor, copy and edit one of the available cpu
|
// For a custom pin map or different processor, copy and edit one of the available cpu
|
||||||
// map files and modify it to your needs. Make sure the defined name is also changed in
|
// map files and modify it to your needs. Make sure the defined name is also changed in
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
defaults.h - defaults settings configuration file
|
defaults.h - defaults settings configuration file
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -19,7 +19,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
/* The defaults.h file serves as a central default settings selector for different machine
|
/* The defaults.h file serves as a central default settings selector for different machine
|
||||||
types, from DIY CNC mills to CNC conversions of off-the-shelf machines. The settings
|
types, from DIY CNC mills to CNC conversions of off-the-shelf machines. The settings
|
||||||
files listed here are supplied by users, so your results may vary. However, this should
|
files listed here are supplied by users, so your results may vary. However, this should
|
||||||
give you a good starting point as you get to know your machine and tweak the settings for
|
give you a good starting point as you get to know your machine and tweak the settings for
|
||||||
your nefarious needs.
|
your nefarious needs.
|
||||||
@ -47,7 +47,7 @@
|
|||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
@ -55,6 +55,8 @@
|
|||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
@ -82,12 +84,12 @@
|
|||||||
#define DEFAULT_Y_MAX_TRAVEL 125.0 // mm
|
#define DEFAULT_Y_MAX_TRAVEL 125.0 // mm
|
||||||
#define DEFAULT_Z_MAX_TRAVEL 170.0 // mm
|
#define DEFAULT_Z_MAX_TRAVEL 170.0 // mm
|
||||||
#define DEFAULT_SPINDLE_RPM_MAX 2800.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MAX 2800.0 // rpm
|
||||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<Y_AXIS)|(1<<Z_AXIS))
|
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<Y_AXIS)|(1<<Z_AXIS))
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // true
|
#define DEFAULT_REPORT_INCHES 0 // true
|
||||||
@ -95,6 +97,8 @@
|
|||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
|
||||||
@ -128,22 +132,24 @@
|
|||||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<Y_AXIS)|(1<<Z_AXIS))
|
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<Y_AXIS)|(1<<Z_AXIS))
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
#define DEFAULT_HOMING_SEEK_RATE 250.0 // mm/min
|
#define DEFAULT_HOMING_SEEK_RATE 250.0 // mm/min
|
||||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef DEFAULTS_SHAPEOKO_2
|
#ifdef DEFAULTS_SHAPEOKO_2
|
||||||
@ -168,25 +174,27 @@
|
|||||||
#define DEFAULT_Y_MAX_TRAVEL 290.0 // mm
|
#define DEFAULT_Y_MAX_TRAVEL 290.0 // mm
|
||||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm
|
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm
|
||||||
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
||||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Z_AXIS))
|
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Z_AXIS))
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
#define DEFAULT_HOMING_SEEK_RATE 250.0 // mm/min
|
#define DEFAULT_HOMING_SEEK_RATE 250.0 // mm/min
|
||||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef DEFAULTS_SHAPEOKO_3
|
#ifdef DEFAULTS_SHAPEOKO_3
|
||||||
@ -215,20 +223,22 @@
|
|||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Z_AXIS))
|
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Z_AXIS))
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK 255 // All enabled
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.01 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.01 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
|
||||||
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
|
#define DEFAULT_HOMING_SEEK_RATE 1000.0 // mm/min
|
||||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 25 // msec (0-65k)
|
#define DEFAULT_HOMING_DEBOUNCE_DELAY 25 // msec (0-65k)
|
||||||
#define DEFAULT_HOMING_PULLOFF 5.0 // mm
|
#define DEFAULT_HOMING_PULLOFF 5.0 // mm
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef DEFAULTS_X_CARVE_500MM
|
#ifdef DEFAULTS_X_CARVE_500MM
|
||||||
@ -253,25 +263,27 @@
|
|||||||
#define DEFAULT_Y_MAX_TRAVEL 290.0 // mm
|
#define DEFAULT_Y_MAX_TRAVEL 290.0 // mm
|
||||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm
|
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm
|
||||||
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
||||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Y_AXIS))
|
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Y_AXIS))
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
#define DEFAULT_HOMING_SEEK_RATE 750.0 // mm/min
|
#define DEFAULT_HOMING_SEEK_RATE 750.0 // mm/min
|
||||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef DEFAULTS_X_CARVE_1000MM
|
#ifdef DEFAULTS_X_CARVE_1000MM
|
||||||
@ -296,25 +308,27 @@
|
|||||||
#define DEFAULT_Y_MAX_TRAVEL 790.0 // mm
|
#define DEFAULT_Y_MAX_TRAVEL 790.0 // mm
|
||||||
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm
|
#define DEFAULT_Z_MAX_TRAVEL 100.0 // mm
|
||||||
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
||||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Y_AXIS))
|
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<X_AXIS)|(1<<Y_AXIS))
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
#define DEFAULT_HOMING_SEEK_RATE 750.0 // mm/min
|
#define DEFAULT_HOMING_SEEK_RATE 750.0 // mm/min
|
||||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef DEFAULTS_ZEN_TOOLWORKS_7x7
|
#ifdef DEFAULTS_ZEN_TOOLWORKS_7x7
|
||||||
@ -337,19 +351,21 @@
|
|||||||
#define DEFAULT_Y_MAX_TRAVEL 180.0 // mm
|
#define DEFAULT_Y_MAX_TRAVEL 180.0 // mm
|
||||||
#define DEFAULT_Z_MAX_TRAVEL 150.0 // mm
|
#define DEFAULT_Z_MAX_TRAVEL 150.0 // mm
|
||||||
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MAX 10000.0 // rpm
|
||||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<Y_AXIS))
|
#define DEFAULT_DIRECTION_INVERT_MASK ((1<<Y_AXIS))
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
@ -374,12 +390,12 @@
|
|||||||
#define DEFAULT_Y_MAX_TRAVEL 750.0 // mm
|
#define DEFAULT_Y_MAX_TRAVEL 750.0 // mm
|
||||||
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm
|
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm
|
||||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.02 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
@ -387,6 +403,8 @@
|
|||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
@ -416,7 +434,7 @@
|
|||||||
#define DEFAULT_STEPPING_INVERT_MASK 0
|
#define DEFAULT_STEPPING_INVERT_MASK 0
|
||||||
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
#define DEFAULT_DIRECTION_INVERT_MASK 0
|
||||||
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
|
||||||
#define DEFAULT_STATUS_REPORT_MASK ((BITFLAG_RT_STATUS_MACHINE_POSITION)|(BITFLAG_RT_STATUS_WORK_POSITION))
|
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled
|
||||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||||
#define DEFAULT_REPORT_INCHES 0 // false
|
#define DEFAULT_REPORT_INCHES 0 // false
|
||||||
@ -424,6 +442,8 @@
|
|||||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||||
|
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||||
|
#define DEFAULT_LASER_MODE 0 // false
|
||||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||||
|
109
grbl/examples/grblWrite_BuildInfo/grblWrite_BuildInfo.ino
Normal file
109
grbl/examples/grblWrite_BuildInfo/grblWrite_BuildInfo.ino
Normal file
@ -0,0 +1,109 @@
|
|||||||
|
/***********************************************************************
|
||||||
|
This sketch writes a `$I` build info string directly into Arduino EEPROM
|
||||||
|
|
||||||
|
To use:
|
||||||
|
- Just alter the "build_info_line" string to whatever you'd like. Then
|
||||||
|
compile and upload this sketch to your Arduino.
|
||||||
|
|
||||||
|
- If your Arduino is blinking slowly, your string has already been
|
||||||
|
written to your EEPROM and been verified by checksums! That's it!
|
||||||
|
|
||||||
|
- If you Arduino LED is blinking fast, something went wrong and the
|
||||||
|
checksums don't match. You can optionally connect to the Arduino via
|
||||||
|
the serial monitor, and the sketch will show what its doing.
|
||||||
|
|
||||||
|
NOTE: This sketch is provided as a tool template for OEMs who may need
|
||||||
|
to restrict users from altering their build info, so they can place
|
||||||
|
important product information here when enabling the restriction.
|
||||||
|
|
||||||
|
NOTE: When uploading Grbl to the Arduino with this sketch on it, make
|
||||||
|
sure you see the slow blink before you start the upload process. This
|
||||||
|
ensures you aren't flashing Grbl when it's in mid-write of the EEPROM.
|
||||||
|
|
||||||
|
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
Released under the MIT-license. See license.txt for details.
|
||||||
|
***********************************************************************/
|
||||||
|
|
||||||
|
#include <avr/pgmspace.h>
|
||||||
|
#include <EEPROM.h>
|
||||||
|
|
||||||
|
#define SERIAL_BAUD_RATE 115200
|
||||||
|
#define LINE_LENGTH 80U // Grbl line length
|
||||||
|
#define BYTE_LOCATION 942U // Grbl build info EEPROM address.
|
||||||
|
|
||||||
|
|
||||||
|
// ----- CHANGE THIS LINE -----
|
||||||
|
|
||||||
|
char build_info_line[LINE_LENGTH] = "Testing123.";
|
||||||
|
|
||||||
|
// -----------------------------
|
||||||
|
|
||||||
|
|
||||||
|
uint8_t status = false;
|
||||||
|
int ledPin = 13; // LED connected to digital pin 13
|
||||||
|
|
||||||
|
void setup() {
|
||||||
|
Serial.begin(SERIAL_BAUD_RATE);
|
||||||
|
delay(500);
|
||||||
|
|
||||||
|
uint32_t address = BYTE_LOCATION;
|
||||||
|
uint32_t size = LINE_LENGTH;
|
||||||
|
char *write_pointer = (char*)build_info_line;
|
||||||
|
uint8_t write_checksum = 0;
|
||||||
|
for (; size>0; size--) {
|
||||||
|
write_checksum = (write_checksum << 1) || (write_checksum >> 7);
|
||||||
|
write_checksum += *write_pointer;
|
||||||
|
EEPROM.put(address++, *(write_pointer++));
|
||||||
|
}
|
||||||
|
EEPROM.put(address,write_checksum);
|
||||||
|
|
||||||
|
Serial.print(F("-> Writing line to EEPROM: '"));
|
||||||
|
Serial.print(build_info_line);
|
||||||
|
Serial.print(F("'\n\r-> Write checksum: "));
|
||||||
|
Serial.println(write_checksum,DEC);
|
||||||
|
|
||||||
|
size = LINE_LENGTH;
|
||||||
|
address = BYTE_LOCATION;
|
||||||
|
uint8_t data = 0;
|
||||||
|
char read_line[LINE_LENGTH];
|
||||||
|
char *read_pointer = (char*)read_line;
|
||||||
|
uint8_t read_checksum = 0;
|
||||||
|
uint8_t stored_checksum = 0;
|
||||||
|
for(; size > 0; size--) {
|
||||||
|
data = EEPROM.read(address++);
|
||||||
|
read_checksum = (read_checksum << 1) || (read_checksum >> 7);
|
||||||
|
read_checksum += data;
|
||||||
|
*(read_pointer++) = data;
|
||||||
|
}
|
||||||
|
stored_checksum = EEPROM.read(address);
|
||||||
|
|
||||||
|
Serial.print(F("<- Reading line from EEPROM: '"));
|
||||||
|
Serial.print(read_line);
|
||||||
|
Serial.print("'\n\r<- Read checksum: ");
|
||||||
|
Serial.println(read_checksum,DEC);
|
||||||
|
|
||||||
|
if ((read_checksum == write_checksum) && (read_checksum == stored_checksum)) {
|
||||||
|
status = true;
|
||||||
|
Serial.print(F("SUCCESS! All checksums match!\r\n"));
|
||||||
|
} else {
|
||||||
|
if (write_checksum != stored_checksum) {
|
||||||
|
Serial.println(F("ERROR! Write and stored EEPROM checksums don't match!"));
|
||||||
|
} else {
|
||||||
|
Serial.println(F("ERROR! Read and stored checksums don't match!"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
pinMode(ledPin, OUTPUT); // sets the digital pin as output
|
||||||
|
}
|
||||||
|
|
||||||
|
void loop() {
|
||||||
|
// Blink to let user know EEPROM write status.
|
||||||
|
// Slow blink is 'ok'. Fast blink is an 'error'.
|
||||||
|
digitalWrite(ledPin, HIGH); // sets the LED on
|
||||||
|
if (status) { delay(1500); } // Slow blink
|
||||||
|
else { delay(100); } // Rapid blink
|
||||||
|
digitalWrite(ledPin, LOW); // sets the LED off
|
||||||
|
if (status) { delay(1500); }
|
||||||
|
else { delay(100); }
|
||||||
|
}
|
||||||
|
|
||||||
|
|
21
grbl/examples/grblWrite_BuildInfo/license.txt
Normal file
21
grbl/examples/grblWrite_BuildInfo/license.txt
Normal file
@ -0,0 +1,21 @@
|
|||||||
|
The MIT License (MIT)
|
||||||
|
|
||||||
|
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
|
Permission is hereby granted, free of charge, to any person obtaining a copy
|
||||||
|
of this software and associated documentation files (the "Software"), to deal
|
||||||
|
in the Software without restriction, including without limitation the rights
|
||||||
|
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
||||||
|
copies of the Software, and to permit persons to whom the Software is
|
||||||
|
furnished to do so, subject to the following conditions:
|
||||||
|
|
||||||
|
The above copyright notice and this permission notice shall be included in
|
||||||
|
all copies or substantial portions of the Software.
|
||||||
|
|
||||||
|
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
||||||
|
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
||||||
|
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
||||||
|
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
||||||
|
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
||||||
|
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
|
||||||
|
THE SOFTWARE.
|
773
grbl/gcode.c
773
grbl/gcode.c
File diff suppressed because it is too large
Load Diff
61
grbl/gcode.h
61
grbl/gcode.h
@ -2,9 +2,9 @@
|
|||||||
gcode.h - rs274/ngc parser.
|
gcode.h - rs274/ngc parser.
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -23,10 +23,10 @@
|
|||||||
#define gcode_h
|
#define gcode_h
|
||||||
|
|
||||||
|
|
||||||
// Define modal group internal numbers for checking multiple command violations and tracking the
|
// Define modal group internal numbers for checking multiple command violations and tracking the
|
||||||
// type of command that is called in the block. A modal group is a group of g-code commands that are
|
// type of command that is called in the block. A modal group is a group of g-code commands that are
|
||||||
// mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute
|
// mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute
|
||||||
// a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online,
|
// a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online,
|
||||||
// and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
|
// and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
|
||||||
// NOTE: Modal group define values must be sequential and starting from zero.
|
// NOTE: Modal group define values must be sequential and starting from zero.
|
||||||
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
|
#define MODAL_GROUP_G0 0 // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
|
||||||
@ -93,8 +93,8 @@
|
|||||||
#define PROGRAM_FLOW_COMPLETED 2 // M2, M30
|
#define PROGRAM_FLOW_COMPLETED 2 // M2, M30
|
||||||
|
|
||||||
// Modal Group G5: Feed rate mode
|
// Modal Group G5: Feed rate mode
|
||||||
#define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
|
#define FEED_RATE_MODE_UNITS_PER_MIN 0 // G94 (Default: Must be zero)
|
||||||
#define FEED_RATE_MODE_INVERSE_TIME 1 // G93
|
#define FEED_RATE_MODE_INVERSE_TIME PL_COND_FLAG_INVERSE_TIME // G93 (NOTE: Uses planner condition bit flag)
|
||||||
|
|
||||||
// Modal Group G6: Units mode
|
// Modal Group G6: Units mode
|
||||||
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
|
#define UNITS_MODE_MM 0 // G21 (Default: Must be zero)
|
||||||
@ -108,13 +108,13 @@
|
|||||||
|
|
||||||
// Modal Group M7: Spindle control
|
// Modal Group M7: Spindle control
|
||||||
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
|
#define SPINDLE_DISABLE 0 // M5 (Default: Must be zero)
|
||||||
#define SPINDLE_ENABLE_CW 1 // M3
|
#define SPINDLE_ENABLE_CW PL_COND_FLAG_SPINDLE_CW // M3 (NOTE: Uses planner condition bit flag)
|
||||||
#define SPINDLE_ENABLE_CCW 2 // M4
|
#define SPINDLE_ENABLE_CCW PL_COND_FLAG_SPINDLE_CCW // M4 (NOTE: Uses planner condition bit flag)
|
||||||
|
|
||||||
// Modal Group M8: Coolant control
|
// Modal Group M8: Coolant control
|
||||||
#define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
|
#define COOLANT_DISABLE 0 // M9 (Default: Must be zero)
|
||||||
#define COOLANT_MIST_ENABLE 1 // M7
|
#define COOLANT_FLOOD_ENABLE PL_COND_FLAG_COOLANT_FLOOD // M8 (NOTE: Uses planner condition bit flag)
|
||||||
#define COOLANT_FLOOD_ENABLE 2 // M8
|
#define COOLANT_MIST_ENABLE PL_COND_FLAG_COOLANT_MIST // M7 (NOTE: Uses planner condition bit flag)
|
||||||
|
|
||||||
// Modal Group G8: Tool length offset
|
// Modal Group G8: Tool length offset
|
||||||
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
#define TOOL_LENGTH_OFFSET_CANCEL 0 // G49 (Default: Must be zero)
|
||||||
@ -123,7 +123,6 @@
|
|||||||
// Modal Group G12: Active work coordinate system
|
// Modal Group G12: Active work coordinate system
|
||||||
// N/A: Stores coordinate system value (54-59) to change to.
|
// N/A: Stores coordinate system value (54-59) to change to.
|
||||||
|
|
||||||
|
|
||||||
// Define parameter word mapping.
|
// Define parameter word mapping.
|
||||||
#define WORD_F 0
|
#define WORD_F 0
|
||||||
#define WORD_I 1
|
#define WORD_I 1
|
||||||
@ -139,6 +138,23 @@
|
|||||||
#define WORD_Y 11
|
#define WORD_Y 11
|
||||||
#define WORD_Z 12
|
#define WORD_Z 12
|
||||||
|
|
||||||
|
// Define g-code parser position updating flags
|
||||||
|
#define GC_UPDATE_POS_TARGET 0
|
||||||
|
#define GC_UPDATE_POS_SYSTEM 1
|
||||||
|
#define GC_UPDATE_POS_NONE 2
|
||||||
|
|
||||||
|
// Define probe cycle exit states and assign proper position updating.
|
||||||
|
#define GC_PROBE_FOUND GC_UPDATE_POS_SYSTEM
|
||||||
|
#define GC_PROBE_ABORT GC_UPDATE_POS_NONE
|
||||||
|
#define GC_PROBE_FAIL_INIT GC_UPDATE_POS_NONE
|
||||||
|
#define GC_PROBE_FAIL_END GC_UPDATE_POS_TARGET
|
||||||
|
#ifdef SET_CHECK_MODE_PROBE_TO_START
|
||||||
|
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_NONE
|
||||||
|
#else
|
||||||
|
#define GC_PROBE_CHECK_MODE GC_UPDATE_POS_TARGET
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// NOTE: When this struct is zeroed, the above defines set the defaults for the system.
|
// NOTE: When this struct is zeroed, the above defines set the defaults for the system.
|
||||||
typedef struct {
|
typedef struct {
|
||||||
@ -155,7 +171,7 @@ typedef struct {
|
|||||||
uint8_t program_flow; // {M0,M1,M2,M30}
|
uint8_t program_flow; // {M0,M1,M2,M30}
|
||||||
uint8_t coolant; // {M7,M8,M9}
|
uint8_t coolant; // {M7,M8,M9}
|
||||||
uint8_t spindle; // {M3,M4,M5}
|
uint8_t spindle; // {M3,M4,M5}
|
||||||
} gc_modal_t;
|
} gc_modal_t;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
float f; // Feed
|
float f; // Feed
|
||||||
@ -173,7 +189,7 @@ typedef struct {
|
|||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
gc_modal_t modal;
|
gc_modal_t modal;
|
||||||
|
|
||||||
float spindle_speed; // RPM
|
float spindle_speed; // RPM
|
||||||
float feed_rate; // Millimeters/min
|
float feed_rate; // Millimeters/min
|
||||||
uint8_t tool; // Tracks tool number. NOT USED.
|
uint8_t tool; // Tracks tool number. NOT USED.
|
||||||
@ -181,24 +197,21 @@ typedef struct {
|
|||||||
|
|
||||||
float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
|
float position[N_AXIS]; // Where the interpreter considers the tool to be at this point in the code
|
||||||
|
|
||||||
float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
|
float coord_system[N_AXIS]; // Current work coordinate system (G54+). Stores offset from absolute machine
|
||||||
// position in mm. Loaded from EEPROM when called.
|
// position in mm. Loaded from EEPROM when called.
|
||||||
float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
|
float coord_offset[N_AXIS]; // Retains the G92 coordinate offset (work coordinates) relative to
|
||||||
// machine zero in mm. Non-persistent. Cleared upon reset and boot.
|
// machine zero in mm. Non-persistent. Cleared upon reset and boot.
|
||||||
float tool_length_offset; // Tracks tool length offset value when enabled.
|
float tool_length_offset; // Tracks tool length offset value when enabled.
|
||||||
} parser_state_t;
|
} parser_state_t;
|
||||||
extern parser_state_t gc_state;
|
extern parser_state_t gc_state;
|
||||||
|
|
||||||
typedef struct {
|
|
||||||
// uint16_t command_words; // NOTE: If this bitflag variable fills, G and M words can be separated.
|
|
||||||
// uint16_t value_words;
|
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
uint8_t non_modal_command;
|
uint8_t non_modal_command;
|
||||||
gc_modal_t modal;
|
gc_modal_t modal;
|
||||||
gc_values_t values;
|
gc_values_t values;
|
||||||
|
|
||||||
} parser_block_t;
|
} parser_block_t;
|
||||||
extern parser_block_t gc_block;
|
|
||||||
|
|
||||||
// Initialize the parser
|
// Initialize the parser
|
||||||
void gc_init();
|
void gc_init();
|
||||||
@ -207,6 +220,6 @@ void gc_init();
|
|||||||
uint8_t gc_execute_line(char *line);
|
uint8_t gc_execute_line(char *line);
|
||||||
|
|
||||||
// Set g-code parser position. Input in steps.
|
// Set g-code parser position. Input in steps.
|
||||||
void gc_sync_position();
|
void gc_sync_position();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
10
grbl/grbl.h
10
grbl/grbl.h
@ -2,7 +2,7 @@
|
|||||||
grbl.h - main Grbl include file
|
grbl.h - main Grbl include file
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2015 Sungeun K. Jeon
|
Copyright (c) 2015-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -22,8 +22,8 @@
|
|||||||
#define grbl_h
|
#define grbl_h
|
||||||
|
|
||||||
// Grbl versioning system
|
// Grbl versioning system
|
||||||
#define GRBL_VERSION "1.0c"
|
#define GRBL_VERSION "1.1c"
|
||||||
#define GRBL_VERSION_BUILD "20160330"
|
#define GRBL_VERSION_BUILD "20161012"
|
||||||
|
|
||||||
// Define standard libraries used by Grbl.
|
// Define standard libraries used by Grbl.
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
@ -32,7 +32,7 @@
|
|||||||
#include <avr/wdt.h>
|
#include <avr/wdt.h>
|
||||||
#include <util/delay.h>
|
#include <util/delay.h>
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include <stdlib.h>
|
#include <stdlib.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
@ -45,6 +45,7 @@
|
|||||||
#include "system.h"
|
#include "system.h"
|
||||||
#include "defaults.h"
|
#include "defaults.h"
|
||||||
#include "cpu_map.h"
|
#include "cpu_map.h"
|
||||||
|
#include "planner.h"
|
||||||
#include "coolant_control.h"
|
#include "coolant_control.h"
|
||||||
#include "eeprom.h"
|
#include "eeprom.h"
|
||||||
#include "gcode.h"
|
#include "gcode.h"
|
||||||
@ -58,5 +59,6 @@
|
|||||||
#include "serial.h"
|
#include "serial.h"
|
||||||
#include "spindle_control.h"
|
#include "spindle_control.h"
|
||||||
#include "stepper.h"
|
#include "stepper.h"
|
||||||
|
#include "jog.h"
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
54
grbl/jog.c
Normal file
54
grbl/jog.c
Normal file
@ -0,0 +1,54 @@
|
|||||||
|
/*
|
||||||
|
jog.h - Jogging methods
|
||||||
|
Part of Grbl
|
||||||
|
|
||||||
|
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
|
(at your option) any later version.
|
||||||
|
|
||||||
|
Grbl is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "grbl.h"
|
||||||
|
|
||||||
|
|
||||||
|
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
|
||||||
|
uint8_t jog_execute(parser_block_t *gc_block)
|
||||||
|
{
|
||||||
|
// Initialize planner data struct for motion blocks.
|
||||||
|
// NOTE: Spindle and coolant are allowed to fully function with overrides during a jog.
|
||||||
|
plan_line_data_t plan_data;
|
||||||
|
plan_line_data_t *pl_data = &plan_data;
|
||||||
|
memset(pl_data,0,sizeof(plan_line_data_t)); // Zero pl_data struct
|
||||||
|
pl_data->feed_rate = gc_block->values.f;
|
||||||
|
pl_data->spindle_speed = gc_block->values.s; // Continue current spindle and coolant condition.
|
||||||
|
plan_data.condition = (PL_COND_FLAG_NO_FEED_OVERRIDE | gc_block->modal.spindle | gc_block->modal.coolant);
|
||||||
|
#ifdef USE_LINE_NUMBERS
|
||||||
|
pl_data->line_number = JOG_LINE_NUMBER;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)) {
|
||||||
|
if (system_check_travel_limits(gc_block->values.xyz)) { return(STATUS_TRAVEL_EXCEEDED); }
|
||||||
|
}
|
||||||
|
|
||||||
|
// Valid jog command. Plan, set state, and execute.
|
||||||
|
mc_line(gc_block->values.xyz,pl_data);
|
||||||
|
if (sys.state == STATE_IDLE) {
|
||||||
|
if (plan_get_current_block() != NULL) { // Check if there is a block to execute.
|
||||||
|
sys.state = STATE_JOG;
|
||||||
|
st_prep_buffer();
|
||||||
|
st_wake_up(); // NOTE: Manual start. No state machine required.
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return(STATUS_OK);
|
||||||
|
}
|
32
grbl/jog.h
Normal file
32
grbl/jog.h
Normal file
@ -0,0 +1,32 @@
|
|||||||
|
/*
|
||||||
|
jog.h - Jogging methods
|
||||||
|
Part of Grbl
|
||||||
|
|
||||||
|
Copyright (c) 2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
|
it under the terms of the GNU General Public License as published by
|
||||||
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
|
(at your option) any later version.
|
||||||
|
|
||||||
|
Grbl is distributed in the hope that it will be useful,
|
||||||
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
GNU General Public License for more details.
|
||||||
|
|
||||||
|
You should have received a copy of the GNU General Public License
|
||||||
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef jog_h
|
||||||
|
#define jog_h
|
||||||
|
|
||||||
|
#include "gcode.h"
|
||||||
|
|
||||||
|
// System motion line numbers must be zero.
|
||||||
|
#define JOG_LINE_NUMBER 0
|
||||||
|
|
||||||
|
// Sets up valid jog motion received from g-code parser, checks for soft-limits, and executes the jog.
|
||||||
|
uint8_t jog_execute(parser_block_t *gc_block);
|
||||||
|
|
||||||
|
#endif
|
258
grbl/limits.c
258
grbl/limits.c
@ -2,9 +2,9 @@
|
|||||||
limits.c - code pertaining to limit-switches and performing the homing cycle
|
limits.c - code pertaining to limit-switches and performing the homing cycle
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -18,7 +18,7 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
|
|
||||||
|
|
||||||
@ -30,7 +30,7 @@
|
|||||||
#define HOMING_AXIS_LOCATE_SCALAR 5.0 // Must be > 1 to ensure limit switch is cleared.
|
#define HOMING_AXIS_LOCATE_SCALAR 5.0 // Must be > 1 to ensure limit switch is cleared.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void limits_init()
|
void limits_init()
|
||||||
{
|
{
|
||||||
LIMIT_DDR &= ~(LIMIT_MASK); // Set as input pins
|
LIMIT_DDR &= ~(LIMIT_MASK); // Set as input pins
|
||||||
|
|
||||||
@ -44,9 +44,9 @@ void limits_init()
|
|||||||
LIMIT_PCMSK |= LIMIT_MASK; // Enable specific pins of the Pin Change Interrupt
|
LIMIT_PCMSK |= LIMIT_MASK; // Enable specific pins of the Pin Change Interrupt
|
||||||
PCICR |= (1 << LIMIT_INT); // Enable Pin Change Interrupt
|
PCICR |= (1 << LIMIT_INT); // Enable Pin Change Interrupt
|
||||||
} else {
|
} else {
|
||||||
limits_disable();
|
limits_disable();
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef ENABLE_SOFTWARE_DEBOUNCE
|
#ifdef ENABLE_SOFTWARE_DEBOUNCE
|
||||||
MCUSR &= ~(1<<WDRF);
|
MCUSR &= ~(1<<WDRF);
|
||||||
WDTCSR |= (1<<WDCE) | (1<<WDE);
|
WDTCSR |= (1<<WDCE) | (1<<WDE);
|
||||||
@ -63,7 +63,7 @@ void limits_disable()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Returns limit state as a bit-wise uint8 variable. Each bit indicates an axis limit, where
|
// Returns limit state as a bit-wise uint8 variable. Each bit indicates an axis limit, where
|
||||||
// triggered is 1 and not triggered is 0. Invert mask is applied. Axes are defined by their
|
// triggered is 1 and not triggered is 0. Invert mask is applied. Axes are defined by their
|
||||||
// number in bit position, i.e. Z_AXIS is (1<<2) or bit 2, and Y_AXIS is (1<<1) or bit 1.
|
// number in bit position, i.e. Z_AXIS is (1<<2) or bit 2, and Y_AXIS is (1<<1) or bit 1.
|
||||||
uint8_t limits_get_state()
|
uint8_t limits_get_state()
|
||||||
@ -74,7 +74,7 @@ uint8_t limits_get_state()
|
|||||||
pin ^= INVERT_LIMIT_PIN_MASK;
|
pin ^= INVERT_LIMIT_PIN_MASK;
|
||||||
#endif
|
#endif
|
||||||
if (bit_isfalse(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { pin ^= LIMIT_MASK; }
|
if (bit_isfalse(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { pin ^= LIMIT_MASK; }
|
||||||
if (pin) {
|
if (pin) {
|
||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
if (pin & get_limit_pin_mask(idx)) { limit_state |= (1 << idx); }
|
if (pin & get_limit_pin_mask(idx)) { limit_state |= (1 << idx); }
|
||||||
@ -84,84 +84,75 @@ uint8_t limits_get_state()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// This is the Limit Pin Change Interrupt, which handles the hard limit feature. A bouncing
|
// This is the Limit Pin Change Interrupt, which handles the hard limit feature. A bouncing
|
||||||
// limit switch can cause a lot of problems, like false readings and multiple interrupt calls.
|
// limit switch can cause a lot of problems, like false readings and multiple interrupt calls.
|
||||||
// If a switch is triggered at all, something bad has happened and treat it as such, regardless
|
// If a switch is triggered at all, something bad has happened and treat it as such, regardless
|
||||||
// if a limit switch is being disengaged. It's impossible to reliably tell the state of a
|
// if a limit switch is being disengaged. It's impossible to reliably tell the state of a
|
||||||
// bouncing pin without a debouncing method. A simple software debouncing feature may be enabled
|
// bouncing pin because the Arduino microcontroller does not retain any state information when
|
||||||
// through the config.h file, where an extra timer delays the limit pin read by several milli-
|
// detecting a pin change. If we poll the pins in the ISR, you can miss the correct reading if the
|
||||||
// seconds to help with, not fix, bouncing switches.
|
// switch is bouncing.
|
||||||
// NOTE: Do not attach an e-stop to the limit pins, because this interrupt is disabled during
|
// NOTE: Do not attach an e-stop to the limit pins, because this interrupt is disabled during
|
||||||
// homing cycles and will not respond correctly. Upon user request or need, there may be a
|
// homing cycles and will not respond correctly. Upon user request or need, there may be a
|
||||||
// special pinout for an e-stop, but it is generally recommended to just directly connect
|
// special pinout for an e-stop, but it is generally recommended to just directly connect
|
||||||
// your e-stop switch to the Arduino reset pin, since it is the most correct way to do this.
|
// your e-stop switch to the Arduino reset pin, since it is the most correct way to do this.
|
||||||
#ifndef ENABLE_SOFTWARE_DEBOUNCE
|
ISR(LIMIT_INT_vect) // DEFAULT: Limit pin change interrupt process.
|
||||||
ISR(LIMIT_INT_vect) // DEFAULT: Limit pin change interrupt process.
|
{
|
||||||
{
|
// Ignore limit switches if already in an alarm state or in-process of executing an alarm.
|
||||||
// Ignore limit switches if already in an alarm state or in-process of executing an alarm.
|
// When in the alarm state, Grbl should have been reset or will force a reset, so any pending
|
||||||
// When in the alarm state, Grbl should have been reset or will force a reset, so any pending
|
// moves in the planner and serial buffers are all cleared and newly sent blocks will be
|
||||||
// moves in the planner and serial buffers are all cleared and newly sent blocks will be
|
// locked out until a homing cycle or a kill lock command. Allows the user to disable the hard
|
||||||
// locked out until a homing cycle or a kill lock command. Allows the user to disable the hard
|
// limit setting if their limits are constantly triggering after a reset and move their axes.
|
||||||
// limit setting if their limits are constantly triggering after a reset and move their axes.
|
if (sys.state != STATE_ALARM) {
|
||||||
if (sys.state != STATE_ALARM) {
|
if (!(sys_rt_exec_alarm)) {
|
||||||
if (!(sys_rt_exec_alarm)) {
|
#ifdef HARD_LIMIT_FORCE_STATE_CHECK
|
||||||
#ifdef HARD_LIMIT_FORCE_STATE_CHECK
|
// Check limit pin state.
|
||||||
// Check limit pin state.
|
|
||||||
if (limits_get_state()) {
|
|
||||||
mc_reset(); // Initiate system kill.
|
|
||||||
system_set_exec_alarm_flag((EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate hard limit critical event
|
|
||||||
}
|
|
||||||
#else
|
|
||||||
mc_reset(); // Initiate system kill.
|
|
||||||
system_set_exec_alarm_flag((EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate hard limit critical event
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
#else // OPTIONAL: Software debounce limit pin routine.
|
|
||||||
// Upon limit pin change, enable watchdog timer to create a short delay.
|
|
||||||
ISR(LIMIT_INT_vect) { if (!(WDTCSR & (1<<WDIE))) { WDTCSR |= (1<<WDIE); } }
|
|
||||||
ISR(WDT_vect) // Watchdog timer ISR
|
|
||||||
{
|
|
||||||
WDTCSR &= ~(1<<WDIE); // Disable watchdog timer.
|
|
||||||
if (sys.state != STATE_ALARM) { // Ignore if already in alarm state.
|
|
||||||
if (!(sys_rt_exec_alarm)) {
|
|
||||||
// Check limit pin state.
|
|
||||||
if (limits_get_state()) {
|
if (limits_get_state()) {
|
||||||
mc_reset(); // Initiate system kill.
|
mc_reset(); // Initiate system kill.
|
||||||
system_set_exec_alarm_flag((EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate hard limit critical event
|
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||||
}
|
}
|
||||||
}
|
#else
|
||||||
|
mc_reset(); // Initiate system kill.
|
||||||
|
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT); // Indicate hard limit critical event
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Homes the specified cycle axes, sets the machine position, and performs a pull-off motion after
|
// Homes the specified cycle axes, sets the machine position, and performs a pull-off motion after
|
||||||
// completing. Homing is a special motion case, which involves rapid uncontrolled stops to locate
|
// completing. Homing is a special motion case, which involves rapid uncontrolled stops to locate
|
||||||
// the trigger point of the limit switches. The rapid stops are handled by a system level axis lock
|
// the trigger point of the limit switches. The rapid stops are handled by a system level axis lock
|
||||||
// mask, which prevents the stepper algorithm from executing step pulses. Homing motions typically
|
// mask, which prevents the stepper algorithm from executing step pulses. Homing motions typically
|
||||||
// circumvent the processes for executing motions in normal operation.
|
// circumvent the processes for executing motions in normal operation.
|
||||||
// NOTE: Only the abort realtime command can interrupt this process.
|
// NOTE: Only the abort realtime command can interrupt this process.
|
||||||
// TODO: Move limit pin-specific calls to a general function for portability.
|
// TODO: Move limit pin-specific calls to a general function for portability.
|
||||||
void limits_go_home(uint8_t cycle_mask)
|
void limits_go_home(uint8_t cycle_mask)
|
||||||
{
|
{
|
||||||
if (sys.abort) { return; } // Block if system reset has been issued.
|
if (sys.abort) { return; } // Block if system reset has been issued.
|
||||||
|
|
||||||
// Initialize
|
// Initialize plan data struct for homing motion. Spindle and coolant are disabled.
|
||||||
|
plan_line_data_t plan_data;
|
||||||
|
plan_line_data_t *pl_data = &plan_data;
|
||||||
|
memset(pl_data,0,sizeof(plan_line_data_t));
|
||||||
|
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||||
|
#ifdef USE_LINE_NUMBERS
|
||||||
|
pl_data->line_number = HOMING_CYCLE_LINE_NUMBER;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Initialize variables used for homing computations.
|
||||||
uint8_t n_cycle = (2*N_HOMING_LOCATE_CYCLE+1);
|
uint8_t n_cycle = (2*N_HOMING_LOCATE_CYCLE+1);
|
||||||
uint8_t step_pin[N_AXIS];
|
uint8_t step_pin[N_AXIS];
|
||||||
float target[N_AXIS];
|
float target[N_AXIS];
|
||||||
float max_travel = 0.0;
|
float max_travel = 0.0;
|
||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
// Initialize step pin masks
|
// Initialize step pin masks
|
||||||
step_pin[idx] = get_step_pin_mask(idx);
|
step_pin[idx] = get_step_pin_mask(idx);
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
if ((idx==A_MOTOR)||(idx==B_MOTOR)) { step_pin[idx] = (get_step_pin_mask(X_AXIS)|get_step_pin_mask(Y_AXIS)); }
|
if ((idx==A_MOTOR)||(idx==B_MOTOR)) { step_pin[idx] = (get_step_pin_mask(X_AXIS)|get_step_pin_mask(Y_AXIS)); }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (bit_istrue(cycle_mask,bit(idx))) {
|
if (bit_istrue(cycle_mask,bit(idx))) {
|
||||||
// Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
|
// Set target based on max_travel setting. Ensure homing switches engaged with search scalar.
|
||||||
// NOTE: settings.max_travel[] is stored as a negative value.
|
// NOTE: settings.max_travel[] is stored as a negative value.
|
||||||
max_travel = max(max_travel,(-HOMING_AXIS_SEARCH_SCALAR)*settings.max_travel[idx]);
|
max_travel = max(max_travel,(-HOMING_AXIS_SEARCH_SCALAR)*settings.max_travel[idx]);
|
||||||
@ -175,7 +166,7 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
uint8_t limit_state, axislock, n_active_axis;
|
uint8_t limit_state, axislock, n_active_axis;
|
||||||
do {
|
do {
|
||||||
|
|
||||||
system_convert_array_steps_to_mpos(target,sys.position);
|
system_convert_array_steps_to_mpos(target,sys_position);
|
||||||
|
|
||||||
// Initialize and declare variables needed for homing routine.
|
// Initialize and declare variables needed for homing routine.
|
||||||
axislock = 0;
|
axislock = 0;
|
||||||
@ -184,16 +175,29 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
// Set target location for active axes and setup computation for homing rate.
|
// Set target location for active axes and setup computation for homing rate.
|
||||||
if (bit_istrue(cycle_mask,bit(idx))) {
|
if (bit_istrue(cycle_mask,bit(idx))) {
|
||||||
n_active_axis++;
|
n_active_axis++;
|
||||||
sys.position[idx] = 0;
|
#ifdef COREXY
|
||||||
|
if (idx == X_AXIS) {
|
||||||
|
int32_t axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||||
|
sys_position[A_MOTOR] = axis_position;
|
||||||
|
sys_position[B_MOTOR] = -axis_position;
|
||||||
|
} else if (idx == Y_AXIS) {
|
||||||
|
int32_t axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||||
|
sys_position[A_MOTOR] = sys_position[B_MOTOR] = axis_position;
|
||||||
|
} else {
|
||||||
|
sys_position[Z_AXIS] = 0;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
sys_position[idx] = 0;
|
||||||
|
#endif
|
||||||
// Set target direction based on cycle mask and homing cycle approach state.
|
// Set target direction based on cycle mask and homing cycle approach state.
|
||||||
// NOTE: This happens to compile smaller than any other implementation tried.
|
// NOTE: This happens to compile smaller than any other implementation tried.
|
||||||
if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
|
if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
|
||||||
if (approach) { target[idx] = -max_travel; }
|
if (approach) { target[idx] = -max_travel; }
|
||||||
else { target[idx] = max_travel; }
|
else { target[idx] = max_travel; }
|
||||||
} else {
|
} else {
|
||||||
if (approach) { target[idx] = max_travel; }
|
if (approach) { target[idx] = max_travel; }
|
||||||
else { target[idx] = -max_travel; }
|
else { target[idx] = -max_travel; }
|
||||||
}
|
}
|
||||||
// Apply axislock to the step port pins active in this cycle.
|
// Apply axislock to the step port pins active in this cycle.
|
||||||
axislock |= step_pin[idx];
|
axislock |= step_pin[idx];
|
||||||
}
|
}
|
||||||
@ -202,15 +206,11 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
|
homing_rate *= sqrt(n_active_axis); // [sqrt(N_AXIS)] Adjust so individual axes all move at homing rate.
|
||||||
sys.homing_axis_lock = axislock;
|
sys.homing_axis_lock = axislock;
|
||||||
|
|
||||||
plan_sync_position(); // Sync planner position to current machine position.
|
|
||||||
|
|
||||||
// Perform homing cycle. Planner buffer should be empty, as required to initiate the homing cycle.
|
// Perform homing cycle. Planner buffer should be empty, as required to initiate the homing cycle.
|
||||||
#ifdef USE_LINE_NUMBERS
|
pl_data->feed_rate = homing_rate; // Set current homing rate.
|
||||||
plan_buffer_line(target, homing_rate, false, false, HOMING_CYCLE_LINE_NUMBER); // Bypass mc_line(). Directly plan homing motion.
|
plan_buffer_line(target, pl_data); // Bypass mc_line(). Directly plan homing motion.
|
||||||
#else
|
|
||||||
plan_buffer_line(target, homing_rate, false, false); // Bypass mc_line(). Directly plan homing motion.
|
sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
|
||||||
#endif
|
|
||||||
|
|
||||||
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
|
st_prep_buffer(); // Prep and fill segment buffer from newly planned block.
|
||||||
st_wake_up(); // Initiate motion
|
st_wake_up(); // Initiate motion
|
||||||
do {
|
do {
|
||||||
@ -219,7 +219,14 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
limit_state = limits_get_state();
|
limit_state = limits_get_state();
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
if (axislock & step_pin[idx]) {
|
if (axislock & step_pin[idx]) {
|
||||||
if (limit_state & (1 << idx)) { axislock &= ~(step_pin[idx]); }
|
if (limit_state & (1 << idx)) {
|
||||||
|
#ifdef COREXY
|
||||||
|
if (idx==Z_AXIS) { axislock &= ~(step_pin[Z_AXIS]); }
|
||||||
|
else { axislock &= ~(step_pin[A_MOTOR]|step_pin[B_MOTOR]); }
|
||||||
|
#else
|
||||||
|
axislock &= ~(step_pin[idx]);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
sys.homing_axis_lock = axislock;
|
sys.homing_axis_lock = axislock;
|
||||||
@ -229,10 +236,16 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
|
|
||||||
// Exit routines: No time to run protocol_execute_realtime() in this loop.
|
// Exit routines: No time to run protocol_execute_realtime() in this loop.
|
||||||
if (sys_rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET | EXEC_CYCLE_STOP)) {
|
if (sys_rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET | EXEC_CYCLE_STOP)) {
|
||||||
// Homing failure: Limit switches are still engaged after pull-off motion
|
uint8_t rt_exec = sys_rt_exec_state;
|
||||||
if ( (sys_rt_exec_state & (EXEC_SAFETY_DOOR | EXEC_RESET)) || // Safety door or reset issued
|
// Homing failure condition: Reset issued during cycle.
|
||||||
(!approach && (limits_get_state() & cycle_mask)) || // Limit switch still engaged after pull-off motion
|
if (rt_exec & EXEC_RESET) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET); }
|
||||||
( approach && (sys_rt_exec_state & EXEC_CYCLE_STOP)) ) { // Limit switch not found during approach.
|
// Homing failure condition: Safety door was opened.
|
||||||
|
if (rt_exec & EXEC_SAFETY_DOOR) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_DOOR); }
|
||||||
|
// Homing failure condition: Limit switch still engaged after pull-off motion
|
||||||
|
if (!approach && (limits_get_state() & cycle_mask)) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_PULLOFF); }
|
||||||
|
// Homing failure condition: Limit switch not found during approach.
|
||||||
|
if (approach && (rt_exec & EXEC_CYCLE_STOP)) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_APPROACH); }
|
||||||
|
if (sys_rt_exec_alarm) {
|
||||||
mc_reset(); // Stop motors, if they are running.
|
mc_reset(); // Stop motors, if they are running.
|
||||||
protocol_execute_realtime();
|
protocol_execute_realtime();
|
||||||
return;
|
return;
|
||||||
@ -240,39 +253,34 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
// Pull-off motion complete. Disable CYCLE_STOP from executing.
|
||||||
system_clear_exec_state_flag(EXEC_CYCLE_STOP);
|
system_clear_exec_state_flag(EXEC_CYCLE_STOP);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
} while (STEP_MASK & axislock);
|
} while (STEP_MASK & axislock);
|
||||||
|
|
||||||
st_reset(); // Immediately force kill steppers and reset step segment buffer.
|
st_reset(); // Immediately force kill steppers and reset step segment buffer.
|
||||||
plan_reset(); // Reset planner buffer to zero planner current position and to clear previous motions.
|
|
||||||
|
|
||||||
delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate.
|
delay_ms(settings.homing_debounce_delay); // Delay to allow transient dynamics to dissipate.
|
||||||
|
|
||||||
// Reverse direction and reset homing rate for locate cycle(s).
|
// Reverse direction and reset homing rate for locate cycle(s).
|
||||||
approach = !approach;
|
approach = !approach;
|
||||||
|
|
||||||
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
|
// After first cycle, homing enters locating phase. Shorten search to pull-off distance.
|
||||||
if (approach) {
|
if (approach) {
|
||||||
max_travel = settings.homing_pulloff*HOMING_AXIS_LOCATE_SCALAR;
|
max_travel = settings.homing_pulloff*HOMING_AXIS_LOCATE_SCALAR;
|
||||||
homing_rate = settings.homing_feed_rate;
|
homing_rate = settings.homing_feed_rate;
|
||||||
} else {
|
} else {
|
||||||
max_travel = settings.homing_pulloff;
|
max_travel = settings.homing_pulloff;
|
||||||
homing_rate = settings.homing_seek_rate;
|
homing_rate = settings.homing_seek_rate;
|
||||||
}
|
}
|
||||||
|
|
||||||
} while (n_cycle-- > 0);
|
} while (n_cycle-- > 0);
|
||||||
|
|
||||||
// The active cycle axes should now be homed and machine limits have been located. By
|
// The active cycle axes should now be homed and machine limits have been located. By
|
||||||
// default, Grbl defines machine space as all negative, as do most CNCs. Since limit switches
|
// default, Grbl defines machine space as all negative, as do most CNCs. Since limit switches
|
||||||
// can be on either side of an axes, check and set axes machine zero appropriately. Also,
|
// can be on either side of an axes, check and set axes machine zero appropriately. Also,
|
||||||
// set up pull-off maneuver from axes limit switches that have been homed. This provides
|
// set up pull-off maneuver from axes limit switches that have been homed. This provides
|
||||||
// some initial clearance off the switches and should also help prevent them from falsely
|
// some initial clearance off the switches and should also help prevent them from falsely
|
||||||
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
|
// triggering when hard limits are enabled or when more than one axes shares a limit pin.
|
||||||
#ifdef COREXY
|
|
||||||
int32_t off_axis_position = 0;
|
|
||||||
#endif
|
|
||||||
int32_t set_axis_position;
|
int32_t set_axis_position;
|
||||||
// Set machine positions for homed limit switches. Don't update non-homed axes.
|
// Set machine positions for homed limit switches. Don't update non-homed axes.
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
@ -280,74 +288,56 @@ void limits_go_home(uint8_t cycle_mask)
|
|||||||
if (cycle_mask & bit(idx)) {
|
if (cycle_mask & bit(idx)) {
|
||||||
#ifdef HOMING_FORCE_SET_ORIGIN
|
#ifdef HOMING_FORCE_SET_ORIGIN
|
||||||
set_axis_position = 0;
|
set_axis_position = 0;
|
||||||
#else
|
#else
|
||||||
if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) {
|
if ( bit_istrue(settings.homing_dir_mask,bit(idx)) ) {
|
||||||
set_axis_position = lround((settings.max_travel[idx]+settings.homing_pulloff)*settings.steps_per_mm[idx]);
|
set_axis_position = lround((settings.max_travel[idx]+settings.homing_pulloff)*settings.steps_per_mm[idx]);
|
||||||
} else {
|
} else {
|
||||||
set_axis_position = lround(-settings.homing_pulloff*settings.steps_per_mm[idx]);
|
set_axis_position = lround(-settings.homing_pulloff*settings.steps_per_mm[idx]);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
if (idx==X_AXIS) {
|
if (idx==X_AXIS) {
|
||||||
off_axis_position = (sys.position[B_MOTOR] - sys.position[A_MOTOR])/2;
|
int32_t off_axis_position = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||||
sys.position[A_MOTOR] = set_axis_position - off_axis_position;
|
sys_position[A_MOTOR] = set_axis_position + off_axis_position;
|
||||||
sys.position[B_MOTOR] = set_axis_position + off_axis_position;
|
sys_position[B_MOTOR] = set_axis_position - off_axis_position;
|
||||||
} else if (idx==Y_AXIS) {
|
} else if (idx==Y_AXIS) {
|
||||||
off_axis_position = (sys.position[A_MOTOR] + sys.position[B_MOTOR])/2;
|
int32_t off_axis_position = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||||
sys.position[A_MOTOR] = off_axis_position - set_axis_position;
|
sys_position[A_MOTOR] = off_axis_position + set_axis_position;
|
||||||
sys.position[B_MOTOR] = off_axis_position + set_axis_position;
|
sys_position[B_MOTOR] = off_axis_position - set_axis_position;
|
||||||
} else {
|
} else {
|
||||||
sys.position[idx] = set_axis_position;
|
sys_position[idx] = set_axis_position;
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
sys.position[idx] = set_axis_position;
|
sys_position[idx] = set_axis_position;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
plan_sync_position(); // Sync planner position to homed machine position.
|
sys.step_control = STEP_CONTROL_NORMAL_OP; // Return step control to normal operation.
|
||||||
|
|
||||||
// sys.state = STATE_HOMING; // Ensure system state set as homing before returning.
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed,
|
// Performs a soft limit check. Called from mc_line() only. Assumes the machine has been homed,
|
||||||
// the workspace volume is in all negative space, and the system is in normal operation.
|
// the workspace volume is in all negative space, and the system is in normal operation.
|
||||||
|
// NOTE: Used by jogging to limit travel within soft-limit volume.
|
||||||
void limits_soft_check(float *target)
|
void limits_soft_check(float *target)
|
||||||
{
|
{
|
||||||
uint8_t idx;
|
if (system_check_travel_limits(target)) {
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
sys.soft_limit = true;
|
||||||
|
// Force feed hold if cycle is active. All buffered blocks are guaranteed to be within
|
||||||
#ifdef HOMING_FORCE_SET_ORIGIN
|
// workspace volume so just come to a controlled stop so position is not lost. When complete
|
||||||
// When homing forced set origin is enabled, soft limits checks need to account for directionality.
|
// enter alarm mode.
|
||||||
// NOTE: max_travel is stored as negative
|
if (sys.state == STATE_CYCLE) {
|
||||||
if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
|
system_set_exec_state_flag(EXEC_FEED_HOLD);
|
||||||
if (target[idx] < 0 || target[idx] > -settings.max_travel[idx]) { sys.soft_limit = true; }
|
do {
|
||||||
} else {
|
protocol_execute_realtime();
|
||||||
if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { sys.soft_limit = true; }
|
if (sys.abort) { return; }
|
||||||
}
|
} while ( sys.state != STATE_IDLE );
|
||||||
#else
|
|
||||||
// NOTE: max_travel is stored as negative
|
|
||||||
if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { sys.soft_limit = true; }
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (sys.soft_limit) {
|
|
||||||
// Force feed hold if cycle is active. All buffered blocks are guaranteed to be within
|
|
||||||
// workspace volume so just come to a controlled stop so position is not lost. When complete
|
|
||||||
// enter alarm mode.
|
|
||||||
if (sys.state == STATE_CYCLE) {
|
|
||||||
system_set_exec_state_flag(EXEC_FEED_HOLD);
|
|
||||||
do {
|
|
||||||
protocol_execute_realtime();
|
|
||||||
if (sys.abort) { return; }
|
|
||||||
} while ( sys.state != STATE_IDLE );
|
|
||||||
}
|
|
||||||
|
|
||||||
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
|
||||||
system_set_exec_alarm_flag((EXEC_ALARM_SOFT_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate soft limit critical event
|
|
||||||
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
|
|
||||||
return;
|
|
||||||
}
|
}
|
||||||
|
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||||
|
system_set_exec_alarm(EXEC_ALARM_SOFT_LIMIT); // Indicate soft limit critical event
|
||||||
|
protocol_execute_realtime(); // Execute to enter critical event loop and system abort
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2,9 +2,9 @@
|
|||||||
limits.h - code pertaining to limit-switches and performing the homing cycle
|
limits.h - code pertaining to limit-switches and performing the homing cycle
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -20,7 +20,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef limits_h
|
#ifndef limits_h
|
||||||
#define limits_h
|
#define limits_h
|
||||||
|
|
||||||
|
|
||||||
// Initialize the limits module
|
// Initialize the limits module
|
||||||
@ -38,4 +38,4 @@ void limits_go_home(uint8_t cycle_mask);
|
|||||||
// Check for soft limit violations
|
// Check for soft limit violations
|
||||||
void limits_soft_check(float *target);
|
void limits_soft_check(float *target);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
40
grbl/main.c
40
grbl/main.c
@ -1,10 +1,10 @@
|
|||||||
/*
|
/*
|
||||||
main.c - An embedded CNC Controller with rs274/ngc (g-code) support
|
main.c - An embedded CNC Controller with rs274/ngc (g-code) support
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -23,7 +23,7 @@
|
|||||||
|
|
||||||
|
|
||||||
// Declare system global variable structure
|
// Declare system global variable structure
|
||||||
system_t sys;
|
system_t sys;
|
||||||
|
|
||||||
|
|
||||||
int main(void)
|
int main(void)
|
||||||
@ -33,7 +33,7 @@ int main(void)
|
|||||||
settings_init(); // Load Grbl settings from EEPROM
|
settings_init(); // Load Grbl settings from EEPROM
|
||||||
stepper_init(); // Configure stepper pins and interrupt timers
|
stepper_init(); // Configure stepper pins and interrupt timers
|
||||||
system_init(); // Configure pinout pins and pin-change interrupt
|
system_init(); // Configure pinout pins and pin-change interrupt
|
||||||
|
|
||||||
memset(&sys, 0, sizeof(system_t)); // Clear all system variables
|
memset(&sys, 0, sizeof(system_t)); // Clear all system variables
|
||||||
sys.abort = true; // Set abort to complete initialization
|
sys.abort = true; // Set abort to complete initialization
|
||||||
sei(); // Enable interrupts
|
sei(); // Enable interrupts
|
||||||
@ -48,25 +48,25 @@ int main(void)
|
|||||||
#ifdef HOMING_INIT_LOCK
|
#ifdef HOMING_INIT_LOCK
|
||||||
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { sys.state = STATE_ALARM; }
|
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) { sys.state = STATE_ALARM; }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Force Grbl into an ALARM state upon a power-cycle or hard reset.
|
// Force Grbl into an ALARM state upon a power-cycle or hard reset.
|
||||||
#ifdef FORCE_INITIALIZATION_ALARM
|
#ifdef FORCE_INITIALIZATION_ALARM
|
||||||
sys.state = STATE_ALARM;
|
sys.state = STATE_ALARM;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Grbl initialization loop upon power-up or a system abort. For the latter, all processes
|
// Grbl initialization loop upon power-up or a system abort. For the latter, all processes
|
||||||
// will return to this loop to be cleanly re-initialized.
|
// will return to this loop to be cleanly re-initialized.
|
||||||
for(;;) {
|
for(;;) {
|
||||||
|
|
||||||
// TODO: Separate configure task that require interrupts to be disabled, especially upon
|
// TODO: Separate configure task that require interrupts to be disabled, especially upon
|
||||||
// a system abort and ensuring any active interrupts are cleanly reset.
|
// a system abort and ensuring any active interrupts are cleanly reset.
|
||||||
|
|
||||||
// Reset Grbl primary systems.
|
// Reset Grbl primary systems.
|
||||||
serial_reset_read_buffer(); // Clear serial read buffer
|
serial_reset_read_buffer(); // Clear serial read buffer
|
||||||
gc_init(); // Set g-code parser to default state
|
gc_init(); // Set g-code parser to default state
|
||||||
spindle_init();
|
spindle_init();
|
||||||
coolant_init();
|
coolant_init();
|
||||||
limits_init();
|
limits_init();
|
||||||
probe_init();
|
probe_init();
|
||||||
plan_reset(); // Clear block buffer and planner variables
|
plan_reset(); // Clear block buffer and planner variables
|
||||||
st_reset(); // Clear stepper subsystem variables.
|
st_reset(); // Clear stepper subsystem variables.
|
||||||
@ -76,15 +76,27 @@ int main(void)
|
|||||||
gc_sync_position();
|
gc_sync_position();
|
||||||
|
|
||||||
// Reset system variables.
|
// Reset system variables.
|
||||||
sys.abort = false;
|
sys.abort = sys.suspend = sys.soft_limit = false;
|
||||||
|
sys.step_control = STEP_CONTROL_NORMAL_OP;
|
||||||
|
sys.f_override = DEFAULT_FEED_OVERRIDE;
|
||||||
|
sys.r_override = DEFAULT_RAPID_OVERRIDE;
|
||||||
|
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE;
|
||||||
|
sys.toggle_ovr_mask = 0;
|
||||||
|
sys.report_wco_counter = REPORT_WCO_REFRESH_BUSY_COUNT; // Set to include in first report.
|
||||||
|
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to include in first report.
|
||||||
|
|
||||||
|
sys_probe_state = 0;
|
||||||
sys_rt_exec_state = 0;
|
sys_rt_exec_state = 0;
|
||||||
sys_rt_exec_alarm = 0;
|
sys_rt_exec_alarm = 0;
|
||||||
sys.suspend = false;
|
sys_rt_exec_motion_override = 0;
|
||||||
sys.soft_limit = false;
|
sys_rt_exec_accessory_override = 0;
|
||||||
|
|
||||||
|
// Print welcome message. Indicates an initialization has occured at power-up or with a reset.
|
||||||
|
report_init_message();
|
||||||
|
|
||||||
// Start Grbl main loop. Processes program inputs and executes them.
|
// Start Grbl main loop. Processes program inputs and executes them.
|
||||||
protocol_main_loop();
|
protocol_main_loop();
|
||||||
|
|
||||||
}
|
}
|
||||||
return 0; /* Never reached */
|
return 0; /* Never reached */
|
||||||
}
|
}
|
||||||
|
@ -2,10 +2,9 @@
|
|||||||
motion_control.c - high level interface for issuing motion commands
|
motion_control.c - high level interface for issuing motion commands
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
Copyright (c) 2011 Simen Svale Skogsrud
|
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -26,38 +25,37 @@
|
|||||||
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
||||||
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
|
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
|
||||||
// (1 minute)/feed_rate time.
|
// (1 minute)/feed_rate time.
|
||||||
// NOTE: This is the primary gateway to the grbl planner. All line motions, including arc line
|
// NOTE: This is the primary gateway to the grbl planner. All line motions, including arc line
|
||||||
// segments, must pass through this routine before being passed to the planner. The seperation of
|
// segments, must pass through this routine before being passed to the planner. The seperation of
|
||||||
// mc_line and plan_buffer_line is done primarily to place non-planner-type functions from being
|
// mc_line and plan_buffer_line is done primarily to place non-planner-type functions from being
|
||||||
// in the planner and to let backlash compensation or canned cycle integration simple and direct.
|
// in the planner and to let backlash compensation or canned cycle integration simple and direct.
|
||||||
#ifdef USE_LINE_NUMBERS
|
void mc_line(float *target, plan_line_data_t *pl_data)
|
||||||
void mc_line(float *target, float feed_rate, uint8_t invert_feed_rate, int32_t line_number)
|
|
||||||
#else
|
|
||||||
void mc_line(float *target, float feed_rate, uint8_t invert_feed_rate)
|
|
||||||
#endif
|
|
||||||
{
|
{
|
||||||
// If enabled, check for soft limit violations. Placed here all line motions are picked up
|
// If enabled, check for soft limit violations. Placed here all line motions are picked up
|
||||||
// from everywhere in Grbl.
|
// from everywhere in Grbl.
|
||||||
if (bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)) { limits_soft_check(target); }
|
if (bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)) {
|
||||||
|
// NOTE: Block jog state. Jogging is a special case and soft limits are handled independently.
|
||||||
|
if (sys.state != STATE_JOG) { limits_soft_check(target); }
|
||||||
|
}
|
||||||
|
|
||||||
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
|
// If in check gcode mode, prevent motion by blocking planner. Soft limits still work.
|
||||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||||
|
|
||||||
// NOTE: Backlash compensation may be installed here. It will need direction info to track when
|
// NOTE: Backlash compensation may be installed here. It will need direction info to track when
|
||||||
// to insert a backlash line motion(s) before the intended line motion and will require its own
|
// to insert a backlash line motion(s) before the intended line motion and will require its own
|
||||||
// plan_check_full_buffer() and check for system abort loop. Also for position reporting
|
// plan_check_full_buffer() and check for system abort loop. Also for position reporting
|
||||||
// backlash steps will need to be also tracked, which will need to be kept at a system level.
|
// backlash steps will need to be also tracked, which will need to be kept at a system level.
|
||||||
// There are likely some other things that will need to be tracked as well. However, we feel
|
// There are likely some other things that will need to be tracked as well. However, we feel
|
||||||
// that backlash compensation should NOT be handled by Grbl itself, because there are a myriad
|
// that backlash compensation should NOT be handled by Grbl itself, because there are a myriad
|
||||||
// of ways to implement it and can be effective or ineffective for different CNC machines. This
|
// of ways to implement it and can be effective or ineffective for different CNC machines. This
|
||||||
// would be better handled by the interface as a post-processor task, where the original g-code
|
// would be better handled by the interface as a post-processor task, where the original g-code
|
||||||
// is translated and inserts backlash motions that best suits the machine.
|
// is translated and inserts backlash motions that best suits the machine.
|
||||||
// NOTE: Perhaps as a middle-ground, all that needs to be sent is a flag or special command that
|
// NOTE: Perhaps as a middle-ground, all that needs to be sent is a flag or special command that
|
||||||
// indicates to Grbl what is a backlash compensation motion, so that Grbl executes the move but
|
// indicates to Grbl what is a backlash compensation motion, so that Grbl executes the move but
|
||||||
// doesn't update the machine position values. Since the position values used by the g-code
|
// doesn't update the machine position values. Since the position values used by the g-code
|
||||||
// parser and planner are separate from the system machine positions, this is doable.
|
// parser and planner are separate from the system machine positions, this is doable.
|
||||||
|
|
||||||
// If the buffer is full: good! That means we are well ahead of the robot.
|
// If the buffer is full: good! That means we are well ahead of the robot.
|
||||||
// Remain in this loop until there is room in the buffer.
|
// Remain in this loop until there is room in the buffer.
|
||||||
do {
|
do {
|
||||||
protocol_execute_realtime(); // Check for any run-time commands
|
protocol_execute_realtime(); // Check for any run-time commands
|
||||||
@ -68,28 +66,19 @@
|
|||||||
|
|
||||||
// Plan and queue motion into planner buffer
|
// Plan and queue motion into planner buffer
|
||||||
// uint8_t plan_status; // Not used in normal operation.
|
// uint8_t plan_status; // Not used in normal operation.
|
||||||
#ifdef USE_LINE_NUMBERS
|
plan_buffer_line(target, pl_data);
|
||||||
plan_buffer_line(target, feed_rate, invert_feed_rate, false, line_number);
|
|
||||||
#else
|
|
||||||
plan_buffer_line(target, feed_rate, invert_feed_rate, false);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
|
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
|
||||||
// offset == offset from current xyz, axis_X defines circle plane in tool space, axis_linear is
|
// offset == offset from current xyz, axis_X defines circle plane in tool space, axis_linear is
|
||||||
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used
|
// the direction of helical travel, radius == circle radius, isclockwise boolean. Used
|
||||||
// for vector transformation direction.
|
// for vector transformation direction.
|
||||||
// The arc is approximated by generating a huge number of tiny, linear segments. The chordal tolerance
|
// The arc is approximated by generating a huge number of tiny, linear segments. The chordal tolerance
|
||||||
// of each segment is configured in settings.arc_tolerance, which is defined to be the maximum normal
|
// of each segment is configured in settings.arc_tolerance, which is defined to be the maximum normal
|
||||||
// distance from segment to the circle when the end points both lie on the circle.
|
// distance from segment to the circle when the end points both lie on the circle.
|
||||||
#ifdef USE_LINE_NUMBERS
|
void mc_arc(float *target, plan_line_data_t *pl_data, float *position, float *offset, float radius,
|
||||||
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
|
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc)
|
||||||
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc, int32_t line_number)
|
|
||||||
#else
|
|
||||||
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
|
|
||||||
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc)
|
|
||||||
#endif
|
|
||||||
{
|
{
|
||||||
float center_axis0 = position[axis_0] + offset[axis_0];
|
float center_axis0 = position[axis_0] + offset[axis_0];
|
||||||
float center_axis1 = position[axis_1] + offset[axis_1];
|
float center_axis1 = position[axis_1] + offset[axis_1];
|
||||||
@ -97,7 +86,7 @@
|
|||||||
float r_axis1 = -offset[axis_1];
|
float r_axis1 = -offset[axis_1];
|
||||||
float rt_axis0 = target[axis_0] - center_axis0;
|
float rt_axis0 = target[axis_0] - center_axis0;
|
||||||
float rt_axis1 = target[axis_1] - center_axis1;
|
float rt_axis1 = target[axis_1] - center_axis1;
|
||||||
|
|
||||||
// CCW angle between position and target from circle center. Only one atan2() trig computation required.
|
// CCW angle between position and target from circle center. Only one atan2() trig computation required.
|
||||||
float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1);
|
float angular_travel = atan2(r_axis0*rt_axis1-r_axis1*rt_axis0, r_axis0*rt_axis0+r_axis1*rt_axis1);
|
||||||
if (is_clockwise_arc) { // Correct atan2 output per direction
|
if (is_clockwise_arc) { // Correct atan2 output per direction
|
||||||
@ -112,13 +101,13 @@
|
|||||||
// For the intended uses of Grbl, this value shouldn't exceed 2000 for the strictest of cases.
|
// For the intended uses of Grbl, this value shouldn't exceed 2000 for the strictest of cases.
|
||||||
uint16_t segments = floor(fabs(0.5*angular_travel*radius)/
|
uint16_t segments = floor(fabs(0.5*angular_travel*radius)/
|
||||||
sqrt(settings.arc_tolerance*(2*radius - settings.arc_tolerance)) );
|
sqrt(settings.arc_tolerance*(2*radius - settings.arc_tolerance)) );
|
||||||
|
|
||||||
if (segments) {
|
if (segments) {
|
||||||
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated
|
// Multiply inverse feed_rate to compensate for the fact that this movement is approximated
|
||||||
// by a number of discrete segments. The inverse feed_rate should be correct for the sum of
|
// by a number of discrete segments. The inverse feed_rate should be correct for the sum of
|
||||||
// all segments.
|
// all segments.
|
||||||
if (invert_feed_rate) { feed_rate *= segments; }
|
if (pl_data->condition & PL_COND_FLAG_INVERSE_TIME) { pl_data->feed_rate *= segments; }
|
||||||
|
|
||||||
float theta_per_segment = angular_travel/segments;
|
float theta_per_segment = angular_travel/segments;
|
||||||
float linear_per_segment = (target[axis_linear] - position[axis_linear])/segments;
|
float linear_per_segment = (target[axis_linear] - position[axis_linear])/segments;
|
||||||
|
|
||||||
@ -126,26 +115,26 @@
|
|||||||
and phi is the angle of rotation. Solution approach by Jens Geisler.
|
and phi is the angle of rotation. Solution approach by Jens Geisler.
|
||||||
r_T = [cos(phi) -sin(phi);
|
r_T = [cos(phi) -sin(phi);
|
||||||
sin(phi) cos(phi] * r ;
|
sin(phi) cos(phi] * r ;
|
||||||
|
|
||||||
For arc generation, the center of the circle is the axis of rotation and the radius vector is
|
For arc generation, the center of the circle is the axis of rotation and the radius vector is
|
||||||
defined from the circle center to the initial position. Each line segment is formed by successive
|
defined from the circle center to the initial position. Each line segment is formed by successive
|
||||||
vector rotations. Single precision values can accumulate error greater than tool precision in rare
|
vector rotations. Single precision values can accumulate error greater than tool precision in rare
|
||||||
cases. So, exact arc path correction is implemented. This approach avoids the problem of too many very
|
cases. So, exact arc path correction is implemented. This approach avoids the problem of too many very
|
||||||
expensive trig operations [sin(),cos(),tan()] which can take 100-200 usec each to compute.
|
expensive trig operations [sin(),cos(),tan()] which can take 100-200 usec each to compute.
|
||||||
|
|
||||||
Small angle approximation may be used to reduce computation overhead further. A third-order approximation
|
Small angle approximation may be used to reduce computation overhead further. A third-order approximation
|
||||||
(second order sin() has too much error) holds for most, if not, all CNC applications. Note that this
|
(second order sin() has too much error) holds for most, if not, all CNC applications. Note that this
|
||||||
approximation will begin to accumulate a numerical drift error when theta_per_segment is greater than
|
approximation will begin to accumulate a numerical drift error when theta_per_segment is greater than
|
||||||
~0.25 rad(14 deg) AND the approximation is successively used without correction several dozen times. This
|
~0.25 rad(14 deg) AND the approximation is successively used without correction several dozen times. This
|
||||||
scenario is extremely unlikely, since segment lengths and theta_per_segment are automatically generated
|
scenario is extremely unlikely, since segment lengths and theta_per_segment are automatically generated
|
||||||
and scaled by the arc tolerance setting. Only a very large arc tolerance setting, unrealistic for CNC
|
and scaled by the arc tolerance setting. Only a very large arc tolerance setting, unrealistic for CNC
|
||||||
applications, would cause this numerical drift error. However, it is best to set N_ARC_CORRECTION from a
|
applications, would cause this numerical drift error. However, it is best to set N_ARC_CORRECTION from a
|
||||||
low of ~4 to a high of ~20 or so to avoid trig operations while keeping arc generation accurate.
|
low of ~4 to a high of ~20 or so to avoid trig operations while keeping arc generation accurate.
|
||||||
|
|
||||||
This approximation also allows mc_arc to immediately insert a line segment into the planner
|
This approximation also allows mc_arc to immediately insert a line segment into the planner
|
||||||
without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
|
without the initial overhead of computing cos() or sin(). By the time the arc needs to be applied
|
||||||
a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead.
|
a correction, the planner should have caught up to the lag caused by the initial mc_arc overhead.
|
||||||
This is important when there are successive arc motions.
|
This is important when there are successive arc motions.
|
||||||
*/
|
*/
|
||||||
// Computes: cos_T = 1 - theta_per_segment^2/2, sin_T = theta_per_segment - theta_per_segment^3/6) in ~52usec
|
// Computes: cos_T = 1 - theta_per_segment^2/2, sin_T = theta_per_segment - theta_per_segment^3/6) in ~52usec
|
||||||
float cos_T = 2.0 - theta_per_segment*theta_per_segment;
|
float cos_T = 2.0 - theta_per_segment*theta_per_segment;
|
||||||
@ -157,16 +146,16 @@
|
|||||||
float r_axisi;
|
float r_axisi;
|
||||||
uint16_t i;
|
uint16_t i;
|
||||||
uint8_t count = 0;
|
uint8_t count = 0;
|
||||||
|
|
||||||
for (i = 1; i<segments; i++) { // Increment (segments-1).
|
for (i = 1; i<segments; i++) { // Increment (segments-1).
|
||||||
|
|
||||||
if (count < N_ARC_CORRECTION) {
|
if (count < N_ARC_CORRECTION) {
|
||||||
// Apply vector rotation matrix. ~40 usec
|
// Apply vector rotation matrix. ~40 usec
|
||||||
r_axisi = r_axis0*sin_T + r_axis1*cos_T;
|
r_axisi = r_axis0*sin_T + r_axis1*cos_T;
|
||||||
r_axis0 = r_axis0*cos_T - r_axis1*sin_T;
|
r_axis0 = r_axis0*cos_T - r_axis1*sin_T;
|
||||||
r_axis1 = r_axisi;
|
r_axis1 = r_axisi;
|
||||||
count++;
|
count++;
|
||||||
} else {
|
} else {
|
||||||
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. ~375 usec
|
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. ~375 usec
|
||||||
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
|
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
|
||||||
cos_Ti = cos(i*theta_per_segment);
|
cos_Ti = cos(i*theta_per_segment);
|
||||||
@ -175,33 +164,25 @@
|
|||||||
r_axis1 = -offset[axis_0]*sin_Ti - offset[axis_1]*cos_Ti;
|
r_axis1 = -offset[axis_0]*sin_Ti - offset[axis_1]*cos_Ti;
|
||||||
count = 0;
|
count = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Update arc_target location
|
// Update arc_target location
|
||||||
position[axis_0] = center_axis0 + r_axis0;
|
position[axis_0] = center_axis0 + r_axis0;
|
||||||
position[axis_1] = center_axis1 + r_axis1;
|
position[axis_1] = center_axis1 + r_axis1;
|
||||||
position[axis_linear] += linear_per_segment;
|
position[axis_linear] += linear_per_segment;
|
||||||
|
|
||||||
#ifdef USE_LINE_NUMBERS
|
mc_line(position, pl_data);
|
||||||
mc_line(position, feed_rate, invert_feed_rate, line_number);
|
|
||||||
#else
|
|
||||||
mc_line(position, feed_rate, invert_feed_rate);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Bail mid-circle on system abort. Runtime command check already performed by mc_line.
|
// Bail mid-circle on system abort. Runtime command check already performed by mc_line.
|
||||||
if (sys.abort) { return; }
|
if (sys.abort) { return; }
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// Ensure last segment arrives at target location.
|
// Ensure last segment arrives at target location.
|
||||||
#ifdef USE_LINE_NUMBERS
|
mc_line(target, pl_data);
|
||||||
mc_line(target, feed_rate, invert_feed_rate, line_number);
|
|
||||||
#else
|
|
||||||
mc_line(target, feed_rate, invert_feed_rate);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Execute dwell in seconds.
|
// Execute dwell in seconds.
|
||||||
void mc_dwell(float seconds)
|
void mc_dwell(float seconds)
|
||||||
{
|
{
|
||||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||||
protocol_buffer_synchronize();
|
protocol_buffer_synchronize();
|
||||||
@ -217,19 +198,19 @@ void mc_homing_cycle()
|
|||||||
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
|
// Check and abort homing cycle, if hard limits are already enabled. Helps prevent problems
|
||||||
// with machines with limits wired on both ends of travel to one limit pin.
|
// with machines with limits wired on both ends of travel to one limit pin.
|
||||||
// TODO: Move the pin-specific LIMIT_PIN call to limits.c as a function.
|
// TODO: Move the pin-specific LIMIT_PIN call to limits.c as a function.
|
||||||
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
|
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
|
||||||
if (limits_get_state()) {
|
if (limits_get_state()) {
|
||||||
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
|
||||||
system_set_exec_alarm_flag((EXEC_ALARM_HARD_LIMIT|EXEC_CRITICAL_EVENT));
|
system_set_exec_alarm(EXEC_ALARM_HARD_LIMIT);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
limits_disable(); // Disable hard limits pin change register for cycle duration
|
limits_disable(); // Disable hard limits pin change register for cycle duration
|
||||||
|
|
||||||
// -------------------------------------------------------------------------------------
|
// -------------------------------------------------------------------------------------
|
||||||
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
// Perform homing routine. NOTE: Special motion case. Only system reset works.
|
||||||
|
|
||||||
// Search to engage all axes limit switches at faster homing seek rate.
|
// Search to engage all axes limit switches at faster homing seek rate.
|
||||||
limits_go_home(HOMING_CYCLE_0); // Homing cycle 0
|
limits_go_home(HOMING_CYCLE_0); // Homing cycle 0
|
||||||
#ifdef HOMING_CYCLE_1
|
#ifdef HOMING_CYCLE_1
|
||||||
@ -238,15 +219,16 @@ void mc_homing_cycle()
|
|||||||
#ifdef HOMING_CYCLE_2
|
#ifdef HOMING_CYCLE_2
|
||||||
limits_go_home(HOMING_CYCLE_2); // Homing cycle 2
|
limits_go_home(HOMING_CYCLE_2); // Homing cycle 2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
protocol_execute_realtime(); // Check for reset and set system abort.
|
protocol_execute_realtime(); // Check for reset and set system abort.
|
||||||
if (sys.abort) { return; } // Did not complete. Alarm state set by mc_alarm.
|
if (sys.abort) { return; } // Did not complete. Alarm state set by mc_alarm.
|
||||||
|
|
||||||
// Homing cycle complete! Setup system for normal operation.
|
// Homing cycle complete! Setup system for normal operation.
|
||||||
// -------------------------------------------------------------------------------------
|
// -------------------------------------------------------------------------------------
|
||||||
|
|
||||||
// Gcode parser position was circumvented by the limits_go_home() routine, so sync position now.
|
// Sync gcode parser and planner positions to homed position.
|
||||||
gc_sync_position();
|
gc_sync_position();
|
||||||
|
plan_sync_position();
|
||||||
|
|
||||||
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
|
// If hard limits feature enabled, re-enable hard limits pin change register after homing cycle.
|
||||||
limits_init();
|
limits_init();
|
||||||
@ -255,102 +237,90 @@ void mc_homing_cycle()
|
|||||||
|
|
||||||
// Perform tool length probe cycle. Requires probe switch.
|
// Perform tool length probe cycle. Requires probe switch.
|
||||||
// NOTE: Upon probe failure, the program will be stopped and placed into ALARM state.
|
// NOTE: Upon probe failure, the program will be stopped and placed into ALARM state.
|
||||||
#ifdef USE_LINE_NUMBERS
|
uint8_t mc_probe_cycle(float *target, plan_line_data_t *pl_data, uint8_t is_probe_away, uint8_t is_no_error)
|
||||||
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
|
{
|
||||||
uint8_t is_no_error, int32_t line_number)
|
|
||||||
#else
|
|
||||||
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
|
|
||||||
uint8_t is_no_error)
|
|
||||||
#endif
|
|
||||||
{
|
|
||||||
// TODO: Need to update this cycle so it obeys a non-auto cycle start.
|
// TODO: Need to update this cycle so it obeys a non-auto cycle start.
|
||||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
if (sys.state == STATE_CHECK_MODE) { return(GC_PROBE_CHECK_MODE); }
|
||||||
|
|
||||||
// Finish all queued commands and empty planner buffer before starting probe cycle.
|
// Finish all queued commands and empty planner buffer before starting probe cycle.
|
||||||
protocol_buffer_synchronize();
|
protocol_buffer_synchronize();
|
||||||
|
if (sys.abort) { return(GC_PROBE_ABORT); } // Return if system reset has been issued.
|
||||||
|
|
||||||
// Initialize probing control variables
|
// Initialize probing control variables
|
||||||
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
sys.probe_succeeded = false; // Re-initialize probe history before beginning cycle.
|
||||||
probe_configure_invert_mask(is_probe_away);
|
probe_configure_invert_mask(is_probe_away);
|
||||||
|
|
||||||
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
|
// After syncing, check if probe is already triggered. If so, halt and issue alarm.
|
||||||
// NOTE: This probe initialization error applies to all probing cycles.
|
// NOTE: This probe initialization error applies to all probing cycles.
|
||||||
if ( probe_get_state() ) { // Check probe pin state.
|
if ( probe_get_state() ) { // Check probe pin state.
|
||||||
system_set_exec_alarm_flag(EXEC_ALARM_PROBE_FAIL);
|
system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_INITIAL);
|
||||||
protocol_execute_realtime();
|
protocol_execute_realtime();
|
||||||
|
probe_configure_invert_mask(false); // Re-initialize invert mask before returning.
|
||||||
|
return(GC_PROBE_FAIL_INIT); // Nothing else to do but bail.
|
||||||
}
|
}
|
||||||
if (sys.abort) { return; } // Return if system reset has been issued.
|
|
||||||
|
|
||||||
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
// Setup and queue probing motion. Auto cycle-start should not start the cycle.
|
||||||
#ifdef USE_LINE_NUMBERS
|
mc_line(target, pl_data);
|
||||||
mc_line(target, feed_rate, invert_feed_rate, line_number);
|
|
||||||
#else
|
|
||||||
mc_line(target, feed_rate, invert_feed_rate);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Activate the probing state monitor in the stepper module.
|
// Activate the probing state monitor in the stepper module.
|
||||||
sys_probe_state = PROBE_ACTIVE;
|
sys_probe_state = PROBE_ACTIVE;
|
||||||
|
|
||||||
// Perform probing cycle. Wait here until probe is triggered or motion completes.
|
// Perform probing cycle. Wait here until probe is triggered or motion completes.
|
||||||
system_set_exec_state_flag(EXEC_CYCLE_START);
|
system_set_exec_state_flag(EXEC_CYCLE_START);
|
||||||
do {
|
do {
|
||||||
protocol_execute_realtime();
|
protocol_execute_realtime();
|
||||||
if (sys.abort) { return; } // Check for system abort
|
if (sys.abort) { return(GC_PROBE_ABORT); } // Check for system abort
|
||||||
} while (sys.state != STATE_IDLE);
|
} while (sys.state != STATE_IDLE);
|
||||||
|
|
||||||
// Probing cycle complete!
|
// Probing cycle complete!
|
||||||
|
|
||||||
// Set state variables and error out, if the probe failed and cycle with error is enabled.
|
// Set state variables and error out, if the probe failed and cycle with error is enabled.
|
||||||
if (sys_probe_state == PROBE_ACTIVE) {
|
if (sys_probe_state == PROBE_ACTIVE) {
|
||||||
if (is_no_error) { memcpy(sys.probe_position, sys.position, sizeof(sys.position)); }
|
if (is_no_error) { memcpy(sys_probe_position, sys_position, sizeof(sys_position)); }
|
||||||
else { system_set_exec_alarm_flag(EXEC_ALARM_PROBE_FAIL); }
|
else { system_set_exec_alarm(EXEC_ALARM_PROBE_FAIL_CONTACT); }
|
||||||
} else {
|
} else {
|
||||||
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
|
sys.probe_succeeded = true; // Indicate to system the probing cycle completed successfully.
|
||||||
}
|
}
|
||||||
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
|
sys_probe_state = PROBE_OFF; // Ensure probe state monitor is disabled.
|
||||||
|
probe_configure_invert_mask(false); // Re-initialize invert mask.
|
||||||
protocol_execute_realtime(); // Check and execute run-time commands
|
protocol_execute_realtime(); // Check and execute run-time commands
|
||||||
if (sys.abort) { return; } // Check for system abort
|
|
||||||
|
|
||||||
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
// Reset the stepper and planner buffers to remove the remainder of the probe motion.
|
||||||
st_reset(); // Reest step segment buffer.
|
st_reset(); // Reset step segment buffer.
|
||||||
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
plan_reset(); // Reset planner buffer. Zero planner positions. Ensure probing motion is cleared.
|
||||||
plan_sync_position(); // Sync planner position to current machine position.
|
plan_sync_position(); // Sync planner position to current machine position.
|
||||||
|
|
||||||
// TODO: Update the g-code parser code to not require this target calculation but uses a gc_sync_position() call.
|
|
||||||
// NOTE: The target[] variable updated here will be sent back and synced with the g-code parser.
|
|
||||||
system_convert_array_steps_to_mpos(target, sys.position);
|
|
||||||
|
|
||||||
#ifdef MESSAGE_PROBE_COORDINATES
|
#ifdef MESSAGE_PROBE_COORDINATES
|
||||||
// All done! Output the probe position as message.
|
// All done! Output the probe position as message.
|
||||||
report_probe_parameters();
|
report_probe_parameters();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
if (sys.probe_succeeded) { return(GC_PROBE_FOUND); } // Successful probe cycle.
|
||||||
|
else { return(GC_PROBE_FAIL_END); } // Failed to trigger probe within travel. With or without error.
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
|
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
|
||||||
// NOTE: Uses the always free planner ring buffer head to store motion parameters for execution.
|
// NOTE: Uses the always free planner ring buffer head to store motion parameters for execution.
|
||||||
void mc_parking_motion(float *parking_target, float feed_rate)
|
void mc_parking_motion(float *parking_target, plan_line_data_t *pl_data)
|
||||||
{
|
{
|
||||||
if (sys.abort) { return; } // Block during abort.
|
if (sys.abort) { return; } // Block during abort.
|
||||||
|
|
||||||
#ifdef USE_LINE_NUMBERS
|
uint8_t plan_status = plan_buffer_line(parking_target, pl_data);
|
||||||
uint8_t plan_status = plan_buffer_line(parking_target, feed_rate, false, true, PARKING_MOTION_LINE_NUMBER);
|
|
||||||
#else
|
|
||||||
uint8_t plan_status = plan_buffer_line(parking_target, feed_rate, false, true);
|
|
||||||
#endif
|
|
||||||
if (plan_status) {
|
if (plan_status) {
|
||||||
bit_true(sys.step_control, STEP_CONTROL_EXECUTE_PARK);
|
bit_true(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||||
bit_false(sys.step_control, STEP_CONTROL_END_MOTION); // Allow parking motion to execute, if feed hold is active.
|
bit_false(sys.step_control, STEP_CONTROL_END_MOTION); // Allow parking motion to execute, if feed hold is active.
|
||||||
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
|
st_parking_setup_buffer(); // Setup step segment buffer for special parking motion case
|
||||||
st_prep_buffer();
|
st_prep_buffer();
|
||||||
st_wake_up();
|
st_wake_up();
|
||||||
do {
|
do {
|
||||||
protocol_exec_rt_system();
|
protocol_exec_rt_system();
|
||||||
if (sys.abort) { return; }
|
if (sys.abort) { return; }
|
||||||
} while (sys.step_control & STEP_CONTROL_EXECUTE_PARK);
|
} while (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||||
st_parking_restore_buffer(); // Restore step segment buffer to normal run state.
|
st_parking_restore_buffer(); // Restore step segment buffer to normal run state.
|
||||||
} else {
|
} else {
|
||||||
bit_false(sys.step_control, STEP_CONTROL_EXECUTE_PARK);
|
bit_false(sys.step_control, STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||||
protocol_exec_rt_system();
|
protocol_exec_rt_system();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -368,18 +338,18 @@ void mc_reset()
|
|||||||
if (bit_isfalse(sys_rt_exec_state, EXEC_RESET)) {
|
if (bit_isfalse(sys_rt_exec_state, EXEC_RESET)) {
|
||||||
system_set_exec_state_flag(EXEC_RESET);
|
system_set_exec_state_flag(EXEC_RESET);
|
||||||
|
|
||||||
// Kill spindle and coolant.
|
// Kill spindle and coolant.
|
||||||
spindle_stop();
|
spindle_stop();
|
||||||
coolant_stop();
|
coolant_set_state(COOLANT_DISABLE);
|
||||||
|
|
||||||
// Kill steppers only if in any motion state, i.e. cycle, actively holding, or homing.
|
// Kill steppers only if in any motion state, i.e. cycle, actively holding, or homing.
|
||||||
// NOTE: If steppers are kept enabled via the step idle delay setting, this also keeps
|
// NOTE: If steppers are kept enabled via the step idle delay setting, this also keeps
|
||||||
// the steppers enabled by avoiding the go_idle call altogether, unless the motion state is
|
// the steppers enabled by avoiding the go_idle call altogether, unless the motion state is
|
||||||
// violated, by which, all bets are off.
|
// violated, by which, all bets are off.
|
||||||
if ((sys.state & (STATE_CYCLE | STATE_HOMING)) ||
|
if ((sys.state & (STATE_CYCLE | STATE_HOMING | STATE_JOG)) ||
|
||||||
(sys.step_control & (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_PARK))) {
|
(sys.step_control & (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION))) {
|
||||||
if (sys.state == STATE_HOMING) { system_set_exec_alarm_flag(EXEC_ALARM_HOMING_FAIL); }
|
if (sys.state == STATE_HOMING) { system_set_exec_alarm(EXEC_ALARM_HOMING_FAIL_RESET); }
|
||||||
else { system_set_exec_alarm_flag(EXEC_ALARM_ABORT_CYCLE); }
|
else { system_set_exec_alarm(EXEC_ALARM_ABORT_CYCLE); }
|
||||||
st_go_idle(); // Force kill steppers. Position has likely been lost.
|
st_go_idle(); // Force kill steppers. Position has likely been lost.
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2,9 +2,9 @@
|
|||||||
motion_control.h - high level interface for issuing motion commands
|
motion_control.h - high level interface for issuing motion commands
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -23,30 +23,22 @@
|
|||||||
#define motion_control_h
|
#define motion_control_h
|
||||||
|
|
||||||
|
|
||||||
#define HOMING_CYCLE_LINE_NUMBER -1
|
// System motion commands must have a line number of zero.
|
||||||
#define PARKING_MOTION_LINE_NUMBER -2
|
#define HOMING_CYCLE_LINE_NUMBER 0
|
||||||
|
#define PARKING_MOTION_LINE_NUMBER 0
|
||||||
|
|
||||||
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
// Execute linear motion in absolute millimeter coordinates. Feed rate given in millimeters/second
|
||||||
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
|
// unless invert_feed_rate is true. Then the feed_rate means that the motion should be completed in
|
||||||
// (1 minute)/feed_rate time.
|
// (1 minute)/feed_rate time.
|
||||||
#ifdef USE_LINE_NUMBERS
|
void mc_line(float *target, plan_line_data_t *pl_data);
|
||||||
void mc_line(float *target, float feed_rate, uint8_t invert_feed_rate, int32_t line_number);
|
|
||||||
#else
|
|
||||||
void mc_line(float *target, float feed_rate, uint8_t invert_feed_rate);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
|
// Execute an arc in offset mode format. position == current xyz, target == target xyz,
|
||||||
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
|
// offset == offset from current xyz, axis_XXX defines circle plane in tool space, axis_linear is
|
||||||
// the direction of helical travel, radius == circle radius, is_clockwise_arc boolean. Used
|
// the direction of helical travel, radius == circle radius, is_clockwise_arc boolean. Used
|
||||||
// for vector transformation direction.
|
// for vector transformation direction.
|
||||||
#ifdef USE_LINE_NUMBERS
|
void mc_arc(float *target, plan_line_data_t *pl_data, float *position, float *offset, float radius,
|
||||||
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
|
uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc);
|
||||||
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc, int32_t line_number);
|
|
||||||
#else
|
|
||||||
void mc_arc(float *position, float *target, float *offset, float radius, float feed_rate,
|
|
||||||
uint8_t invert_feed_rate, uint8_t axis_0, uint8_t axis_1, uint8_t axis_linear, uint8_t is_clockwise_arc);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Dwell for a specific number of seconds
|
// Dwell for a specific number of seconds
|
||||||
void mc_dwell(float seconds);
|
void mc_dwell(float seconds);
|
||||||
|
|
||||||
@ -54,16 +46,10 @@ void mc_dwell(float seconds);
|
|||||||
void mc_homing_cycle();
|
void mc_homing_cycle();
|
||||||
|
|
||||||
// Perform tool length probe cycle. Requires probe switch.
|
// Perform tool length probe cycle. Requires probe switch.
|
||||||
#ifdef USE_LINE_NUMBERS
|
uint8_t mc_probe_cycle(float *target, plan_line_data_t *pl_data, uint8_t is_probe_away, uint8_t is_no_error);
|
||||||
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
|
|
||||||
uint8_t is_no_error, int32_t line_number);
|
|
||||||
#else
|
|
||||||
void mc_probe_cycle(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_probe_away,
|
|
||||||
uint8_t is_no_error);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
|
// Plans and executes the single special motion case for parking. Independent of main planner buffer.
|
||||||
void mc_parking_motion(float *parking_target, float feed_rate);
|
void mc_parking_motion(float *parking_target, plan_line_data_t *pl_data);
|
||||||
|
|
||||||
// Performs system reset. If in motion state, kills all motion and sets system alarm.
|
// Performs system reset. If in motion state, kills all motion and sets system alarm.
|
||||||
void mc_reset();
|
void mc_reset();
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
nuts_bolts.c - Shared functions
|
nuts_bolts.c - Shared functions
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -30,16 +30,16 @@
|
|||||||
// available conversion method examples, but has been highly optimized for Grbl. For known
|
// available conversion method examples, but has been highly optimized for Grbl. For known
|
||||||
// CNC applications, the typical decimal value is expected to be in the range of E0 to E-4.
|
// CNC applications, the typical decimal value is expected to be in the range of E0 to E-4.
|
||||||
// Scientific notation is officially not supported by g-code, and the 'E' character may
|
// Scientific notation is officially not supported by g-code, and the 'E' character may
|
||||||
// be a g-code word on some CNC systems. So, 'E' notation will not be recognized.
|
// be a g-code word on some CNC systems. So, 'E' notation will not be recognized.
|
||||||
// NOTE: Thanks to Radu-Eosif Mihailescu for identifying the issues with using strtod().
|
// NOTE: Thanks to Radu-Eosif Mihailescu for identifying the issues with using strtod().
|
||||||
uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr)
|
uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr)
|
||||||
{
|
{
|
||||||
char *ptr = line + *char_counter;
|
char *ptr = line + *char_counter;
|
||||||
unsigned char c;
|
unsigned char c;
|
||||||
|
|
||||||
// Grab first character and increment pointer. No spaces assumed in line.
|
// Grab first character and increment pointer. No spaces assumed in line.
|
||||||
c = *ptr++;
|
c = *ptr++;
|
||||||
|
|
||||||
// Capture initial positive/minus character
|
// Capture initial positive/minus character
|
||||||
bool isnegative = false;
|
bool isnegative = false;
|
||||||
if (c == '-') {
|
if (c == '-') {
|
||||||
@ -48,7 +48,7 @@ uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr)
|
|||||||
} else if (c == '+') {
|
} else if (c == '+') {
|
||||||
c = *ptr++;
|
c = *ptr++;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Extract number into fast integer. Track decimal in terms of exponent value.
|
// Extract number into fast integer. Track decimal in terms of exponent value.
|
||||||
uint32_t intval = 0;
|
uint32_t intval = 0;
|
||||||
int8_t exp = 0;
|
int8_t exp = 0;
|
||||||
@ -71,31 +71,31 @@ uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr)
|
|||||||
}
|
}
|
||||||
c = *ptr++;
|
c = *ptr++;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return if no digits have been read.
|
// Return if no digits have been read.
|
||||||
if (!ndigit) { return(false); };
|
if (!ndigit) { return(false); };
|
||||||
|
|
||||||
// Convert integer into floating point.
|
// Convert integer into floating point.
|
||||||
float fval;
|
float fval;
|
||||||
fval = (float)intval;
|
fval = (float)intval;
|
||||||
|
|
||||||
// Apply decimal. Should perform no more than two floating point multiplications for the
|
// Apply decimal. Should perform no more than two floating point multiplications for the
|
||||||
// expected range of E0 to E-4.
|
// expected range of E0 to E-4.
|
||||||
if (fval != 0) {
|
if (fval != 0) {
|
||||||
while (exp <= -2) {
|
while (exp <= -2) {
|
||||||
fval *= 0.01;
|
fval *= 0.01;
|
||||||
exp += 2;
|
exp += 2;
|
||||||
}
|
}
|
||||||
if (exp < 0) {
|
if (exp < 0) {
|
||||||
fval *= 0.1;
|
fval *= 0.1;
|
||||||
} else if (exp > 0) {
|
} else if (exp > 0) {
|
||||||
do {
|
do {
|
||||||
fval *= 10.0;
|
fval *= 10.0;
|
||||||
} while (--exp > 0);
|
} while (--exp > 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Assign floating point value with correct sign.
|
// Assign floating point value with correct sign.
|
||||||
if (isnegative) {
|
if (isnegative) {
|
||||||
*float_ptr = -fval;
|
*float_ptr = -fval;
|
||||||
} else {
|
} else {
|
||||||
@ -103,7 +103,7 @@ uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr)
|
|||||||
}
|
}
|
||||||
|
|
||||||
*char_counter = ptr - line - 1; // Set char_counter to next statement
|
*char_counter = ptr - line - 1; // Set char_counter to next statement
|
||||||
|
|
||||||
return(true);
|
return(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -116,7 +116,7 @@ void delay_sec(float seconds, uint8_t mode)
|
|||||||
if (sys.abort) { return; }
|
if (sys.abort) { return; }
|
||||||
if (mode == DELAY_MODE_DWELL) {
|
if (mode == DELAY_MODE_DWELL) {
|
||||||
protocol_execute_realtime();
|
protocol_execute_realtime();
|
||||||
} else { // DELAY_MODE_SAFETY_DOOR
|
} else { // DELAY_MODE_SYS_SUSPEND
|
||||||
// Execute rt_system() only to avoid nesting suspend loops.
|
// Execute rt_system() only to avoid nesting suspend loops.
|
||||||
protocol_exec_rt_system();
|
protocol_exec_rt_system();
|
||||||
if (sys.suspend & SUSPEND_RESTART_RETRACT) { return; } // Bail, if safety door reopens.
|
if (sys.suspend & SUSPEND_RESTART_RETRACT) { return; } // Bail, if safety door reopens.
|
||||||
@ -128,19 +128,19 @@ void delay_sec(float seconds, uint8_t mode)
|
|||||||
|
|
||||||
// Delays variable defined milliseconds. Compiler compatibility fix for _delay_ms(),
|
// Delays variable defined milliseconds. Compiler compatibility fix for _delay_ms(),
|
||||||
// which only accepts constants in future compiler releases.
|
// which only accepts constants in future compiler releases.
|
||||||
void delay_ms(uint16_t ms)
|
void delay_ms(uint16_t ms)
|
||||||
{
|
{
|
||||||
while ( ms-- ) { _delay_ms(1); }
|
while ( ms-- ) { _delay_ms(1); }
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Delays variable defined microseconds. Compiler compatibility fix for _delay_us(),
|
// Delays variable defined microseconds. Compiler compatibility fix for _delay_us(),
|
||||||
// which only accepts constants in future compiler releases. Written to perform more
|
// which only accepts constants in future compiler releases. Written to perform more
|
||||||
// efficiently with larger delays, as the counter adds parasitic time in each iteration.
|
// efficiently with larger delays, as the counter adds parasitic time in each iteration.
|
||||||
void delay_us(uint32_t us)
|
void delay_us(uint32_t us)
|
||||||
{
|
{
|
||||||
while (us) {
|
while (us) {
|
||||||
if (us < 10) {
|
if (us < 10) {
|
||||||
_delay_us(1);
|
_delay_us(1);
|
||||||
us--;
|
us--;
|
||||||
} else if (us < 100) {
|
} else if (us < 100) {
|
||||||
@ -159,3 +159,32 @@ void delay_us(uint32_t us)
|
|||||||
|
|
||||||
// Simple hypotenuse computation function.
|
// Simple hypotenuse computation function.
|
||||||
float hypot_f(float x, float y) { return(sqrt(x*x + y*y)); }
|
float hypot_f(float x, float y) { return(sqrt(x*x + y*y)); }
|
||||||
|
|
||||||
|
|
||||||
|
float convert_delta_vector_to_unit_vector(float *vector)
|
||||||
|
{
|
||||||
|
uint8_t idx;
|
||||||
|
float magnitude = 0.0;
|
||||||
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
|
if (vector[idx] != 0.0) {
|
||||||
|
magnitude += vector[idx]*vector[idx];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
magnitude = sqrt(magnitude);
|
||||||
|
float inv_magnitude = 1.0/magnitude;
|
||||||
|
for (idx=0; idx<N_AXIS; idx++) { vector[idx] *= inv_magnitude; }
|
||||||
|
return(magnitude);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
float limit_value_by_axis_maximum(float *max_value, float *unit_vec)
|
||||||
|
{
|
||||||
|
uint8_t idx;
|
||||||
|
float limit_value = SOME_LARGE_VALUE;
|
||||||
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
|
if (unit_vec[idx] != 0) { // Avoid divide by zero.
|
||||||
|
limit_value = min(limit_value,fabs(max_value[idx]/unit_vec[idx]));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return(limit_value);
|
||||||
|
}
|
||||||
|
@ -2,8 +2,8 @@
|
|||||||
nuts_bolts.h - Header file for shared definitions, variables, and functions
|
nuts_bolts.h - Header file for shared definitions, variables, and functions
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -25,9 +25,11 @@
|
|||||||
#define false 0
|
#define false 0
|
||||||
#define true 1
|
#define true 1
|
||||||
|
|
||||||
|
#define SOME_LARGE_VALUE 1.0E+38
|
||||||
|
|
||||||
// Axis array index values. Must start with 0 and be continuous.
|
// Axis array index values. Must start with 0 and be continuous.
|
||||||
#define N_AXIS 3 // Number of axes
|
#define N_AXIS 3 // Number of axes
|
||||||
#define X_AXIS 0 // Axis indexing value.
|
#define X_AXIS 0 // Axis indexing value.
|
||||||
#define Y_AXIS 1
|
#define Y_AXIS 1
|
||||||
#define Z_AXIS 2
|
#define Z_AXIS 2
|
||||||
// #define A_AXIS 3
|
// #define A_AXIS 3
|
||||||
@ -45,7 +47,7 @@
|
|||||||
#define TICKS_PER_MICROSECOND (F_CPU/1000000)
|
#define TICKS_PER_MICROSECOND (F_CPU/1000000)
|
||||||
|
|
||||||
#define DELAY_MODE_DWELL 0
|
#define DELAY_MODE_DWELL 0
|
||||||
#define DELAY_MODE_SAFETY_DOOR 1
|
#define DELAY_MODE_SYS_SUSPEND 1
|
||||||
|
|
||||||
// Useful macros
|
// Useful macros
|
||||||
#define clear_vector(a) memset(a, 0, sizeof(a))
|
#define clear_vector(a) memset(a, 0, sizeof(a))
|
||||||
@ -53,16 +55,17 @@
|
|||||||
// #define clear_vector_long(a) memset(a, 0.0, sizeof(long)*N_AXIS)
|
// #define clear_vector_long(a) memset(a, 0.0, sizeof(long)*N_AXIS)
|
||||||
#define max(a,b) (((a) > (b)) ? (a) : (b))
|
#define max(a,b) (((a) > (b)) ? (a) : (b))
|
||||||
#define min(a,b) (((a) < (b)) ? (a) : (b))
|
#define min(a,b) (((a) < (b)) ? (a) : (b))
|
||||||
|
#define isequal_position_vector(a,b) !(memcmp(a, b, sizeof(float)*N_AXIS))
|
||||||
|
|
||||||
// Bit field and masking macros
|
// Bit field and masking macros
|
||||||
#define bit(n) (1 << n)
|
#define bit(n) (1 << n)
|
||||||
#define bit_true(x,mask) (x) |= (mask)
|
#define bit_true(x,mask) (x) |= (mask)
|
||||||
#define bit_false(x,mask) (x) &= ~(mask)
|
#define bit_false(x,mask) (x) &= ~(mask)
|
||||||
#define bit_istrue(x,mask) ((x & mask) != 0)
|
#define bit_istrue(x,mask) ((x & mask) != 0)
|
||||||
#define bit_isfalse(x,mask) ((x & mask) == 0)
|
#define bit_isfalse(x,mask) ((x & mask) == 0)
|
||||||
|
|
||||||
// Read a floating point value from a string. Line points to the input buffer, char_counter
|
// Read a floating point value from a string. Line points to the input buffer, char_counter
|
||||||
// is the indexer pointing to the current character of the line, while float_ptr is
|
// is the indexer pointing to the current character of the line, while float_ptr is
|
||||||
// a pointer to the result variable. Returns true when it succeeds
|
// a pointer to the result variable. Returns true when it succeeds
|
||||||
uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr);
|
uint8_t read_float(char *line, uint8_t *char_counter, float *float_ptr);
|
||||||
|
|
||||||
@ -78,4 +81,7 @@ void delay_us(uint32_t us);
|
|||||||
// Computes hypotenuse, avoiding avr-gcc's bloated version and the extra error checking.
|
// Computes hypotenuse, avoiding avr-gcc's bloated version and the extra error checking.
|
||||||
float hypot_f(float x, float y);
|
float hypot_f(float x, float y);
|
||||||
|
|
||||||
|
float convert_delta_vector_to_unit_vector(float *vector);
|
||||||
|
float limit_value_by_axis_maximum(float *max_value, float *unit_vec);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
376
grbl/planner.c
376
grbl/planner.c
@ -2,10 +2,10 @@
|
|||||||
planner.c - buffers movement commands and manages the acceleration profile plan
|
planner.c - buffers movement commands and manages the acceleration profile plan
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
Copyright (c) 2011 Jens Geisler
|
Copyright (c) 2011 Jens Geisler
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -22,8 +22,6 @@
|
|||||||
|
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
|
|
||||||
#define SOME_LARGE_VALUE 1.0E+38 // Used by rapids and acceleration maximization calculations. Just needs
|
|
||||||
// to be larger than any feasible (mm/min)^2 or mm/sec^2 value.
|
|
||||||
|
|
||||||
static plan_block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions
|
static plan_block_t block_buffer[BLOCK_BUFFER_SIZE]; // A ring buffer for motion instructions
|
||||||
static uint8_t block_buffer_tail; // Index of the block to process now
|
static uint8_t block_buffer_tail; // Index of the block to process now
|
||||||
@ -37,13 +35,13 @@ typedef struct {
|
|||||||
// from g-code position for movements requiring multiple line motions,
|
// from g-code position for movements requiring multiple line motions,
|
||||||
// i.e. arcs, canned cycles, and backlash compensation.
|
// i.e. arcs, canned cycles, and backlash compensation.
|
||||||
float previous_unit_vec[N_AXIS]; // Unit vector of previous path line segment
|
float previous_unit_vec[N_AXIS]; // Unit vector of previous path line segment
|
||||||
float previous_nominal_speed_sqr; // Nominal speed of previous path line segment
|
float previous_nominal_speed; // Nominal speed of previous path line segment
|
||||||
} planner_t;
|
} planner_t;
|
||||||
static planner_t pl;
|
static planner_t pl;
|
||||||
|
|
||||||
|
|
||||||
// Returns the index of the next block in the ring buffer. Also called by stepper segment buffer.
|
// Returns the index of the next block in the ring buffer. Also called by stepper segment buffer.
|
||||||
uint8_t plan_next_block_index(uint8_t block_index)
|
uint8_t plan_next_block_index(uint8_t block_index)
|
||||||
{
|
{
|
||||||
block_index++;
|
block_index++;
|
||||||
if (block_index == BLOCK_BUFFER_SIZE) { block_index = 0; }
|
if (block_index == BLOCK_BUFFER_SIZE) { block_index = 0; }
|
||||||
@ -52,7 +50,7 @@ uint8_t plan_next_block_index(uint8_t block_index)
|
|||||||
|
|
||||||
|
|
||||||
// Returns the index of the previous block in the ring buffer
|
// Returns the index of the previous block in the ring buffer
|
||||||
static uint8_t plan_prev_block_index(uint8_t block_index)
|
static uint8_t plan_prev_block_index(uint8_t block_index)
|
||||||
{
|
{
|
||||||
if (block_index == 0) { block_index = BLOCK_BUFFER_SIZE; }
|
if (block_index == 0) { block_index = BLOCK_BUFFER_SIZE; }
|
||||||
block_index--;
|
block_index--;
|
||||||
@ -60,64 +58,64 @@ static uint8_t plan_prev_block_index(uint8_t block_index)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/* PLANNER SPEED DEFINITION
|
/* PLANNER SPEED DEFINITION
|
||||||
+--------+ <- current->nominal_speed
|
+--------+ <- current->nominal_speed
|
||||||
/ \
|
/ \
|
||||||
current->entry_speed -> + \
|
current->entry_speed -> + \
|
||||||
| + <- next->entry_speed (aka exit speed)
|
| + <- next->entry_speed (aka exit speed)
|
||||||
+-------------+
|
+-------------+
|
||||||
time -->
|
time -->
|
||||||
|
|
||||||
Recalculates the motion plan according to the following basic guidelines:
|
Recalculates the motion plan according to the following basic guidelines:
|
||||||
|
|
||||||
1. Go over every feasible block sequentially in reverse order and calculate the junction speeds
|
1. Go over every feasible block sequentially in reverse order and calculate the junction speeds
|
||||||
(i.e. current->entry_speed) such that:
|
(i.e. current->entry_speed) such that:
|
||||||
a. No junction speed exceeds the pre-computed maximum junction speed limit or nominal speeds of
|
a. No junction speed exceeds the pre-computed maximum junction speed limit or nominal speeds of
|
||||||
neighboring blocks.
|
neighboring blocks.
|
||||||
b. A block entry speed cannot exceed one reverse-computed from its exit speed (next->entry_speed)
|
b. A block entry speed cannot exceed one reverse-computed from its exit speed (next->entry_speed)
|
||||||
with a maximum allowable deceleration over the block travel distance.
|
with a maximum allowable deceleration over the block travel distance.
|
||||||
c. The last (or newest appended) block is planned from a complete stop (an exit speed of zero).
|
c. The last (or newest appended) block is planned from a complete stop (an exit speed of zero).
|
||||||
2. Go over every block in chronological (forward) order and dial down junction speed values if
|
2. Go over every block in chronological (forward) order and dial down junction speed values if
|
||||||
a. The exit speed exceeds the one forward-computed from its entry speed with the maximum allowable
|
a. The exit speed exceeds the one forward-computed from its entry speed with the maximum allowable
|
||||||
acceleration over the block travel distance.
|
acceleration over the block travel distance.
|
||||||
|
|
||||||
When these stages are complete, the planner will have maximized the velocity profiles throughout the all
|
When these stages are complete, the planner will have maximized the velocity profiles throughout the all
|
||||||
of the planner blocks, where every block is operating at its maximum allowable acceleration limits. In
|
of the planner blocks, where every block is operating at its maximum allowable acceleration limits. In
|
||||||
other words, for all of the blocks in the planner, the plan is optimal and no further speed improvements
|
other words, for all of the blocks in the planner, the plan is optimal and no further speed improvements
|
||||||
are possible. If a new block is added to the buffer, the plan is recomputed according to the said
|
are possible. If a new block is added to the buffer, the plan is recomputed according to the said
|
||||||
guidelines for a new optimal plan.
|
guidelines for a new optimal plan.
|
||||||
|
|
||||||
To increase computational efficiency of these guidelines, a set of planner block pointers have been
|
To increase computational efficiency of these guidelines, a set of planner block pointers have been
|
||||||
created to indicate stop-compute points for when the planner guidelines cannot logically make any further
|
created to indicate stop-compute points for when the planner guidelines cannot logically make any further
|
||||||
changes or improvements to the plan when in normal operation and new blocks are streamed and added to the
|
changes or improvements to the plan when in normal operation and new blocks are streamed and added to the
|
||||||
planner buffer. For example, if a subset of sequential blocks in the planner have been planned and are
|
planner buffer. For example, if a subset of sequential blocks in the planner have been planned and are
|
||||||
bracketed by junction velocities at their maximums (or by the first planner block as well), no new block
|
bracketed by junction velocities at their maximums (or by the first planner block as well), no new block
|
||||||
added to the planner buffer will alter the velocity profiles within them. So we no longer have to compute
|
added to the planner buffer will alter the velocity profiles within them. So we no longer have to compute
|
||||||
them. Or, if a set of sequential blocks from the first block in the planner (or a optimal stop-compute
|
them. Or, if a set of sequential blocks from the first block in the planner (or a optimal stop-compute
|
||||||
point) are all accelerating, they are all optimal and can not be altered by a new block added to the
|
point) are all accelerating, they are all optimal and can not be altered by a new block added to the
|
||||||
planner buffer, as this will only further increase the plan speed to chronological blocks until a maximum
|
planner buffer, as this will only further increase the plan speed to chronological blocks until a maximum
|
||||||
junction velocity is reached. However, if the operational conditions of the plan changes from infrequently
|
junction velocity is reached. However, if the operational conditions of the plan changes from infrequently
|
||||||
used feed holds or feedrate overrides, the stop-compute pointers will be reset and the entire plan is
|
used feed holds or feedrate overrides, the stop-compute pointers will be reset and the entire plan is
|
||||||
recomputed as stated in the general guidelines.
|
recomputed as stated in the general guidelines.
|
||||||
|
|
||||||
Planner buffer index mapping:
|
Planner buffer index mapping:
|
||||||
- block_buffer_tail: Points to the beginning of the planner buffer. First to be executed or being executed.
|
- block_buffer_tail: Points to the beginning of the planner buffer. First to be executed or being executed.
|
||||||
- block_buffer_head: Points to the buffer block after the last block in the buffer. Used to indicate whether
|
- block_buffer_head: Points to the buffer block after the last block in the buffer. Used to indicate whether
|
||||||
the buffer is full or empty. As described for standard ring buffers, this block is always empty.
|
the buffer is full or empty. As described for standard ring buffers, this block is always empty.
|
||||||
- next_buffer_head: Points to next planner buffer block after the buffer head block. When equal to the
|
- next_buffer_head: Points to next planner buffer block after the buffer head block. When equal to the
|
||||||
buffer tail, this indicates the buffer is full.
|
buffer tail, this indicates the buffer is full.
|
||||||
- block_buffer_planned: Points to the first buffer block after the last optimally planned block for normal
|
- block_buffer_planned: Points to the first buffer block after the last optimally planned block for normal
|
||||||
streaming operating conditions. Use for planning optimizations by avoiding recomputing parts of the
|
streaming operating conditions. Use for planning optimizations by avoiding recomputing parts of the
|
||||||
planner buffer that don't change with the addition of a new block, as describe above. In addition,
|
planner buffer that don't change with the addition of a new block, as describe above. In addition,
|
||||||
this block can never be less than block_buffer_tail and will always be pushed forward and maintain
|
this block can never be less than block_buffer_tail and will always be pushed forward and maintain
|
||||||
this requirement when encountered by the plan_discard_current_block() routine during a cycle.
|
this requirement when encountered by the plan_discard_current_block() routine during a cycle.
|
||||||
|
|
||||||
NOTE: Since the planner only computes on what's in the planner buffer, some motions with lots of short
|
NOTE: Since the planner only computes on what's in the planner buffer, some motions with lots of short
|
||||||
line segments, like G2/3 arcs or complex curves, may seem to move slow. This is because there simply isn't
|
line segments, like G2/3 arcs or complex curves, may seem to move slow. This is because there simply isn't
|
||||||
enough combined distance traveled in the entire buffer to accelerate up to the nominal speed and then
|
enough combined distance traveled in the entire buffer to accelerate up to the nominal speed and then
|
||||||
decelerate to a complete stop at the end of the buffer, as stated by the guidelines. If this happens and
|
decelerate to a complete stop at the end of the buffer, as stated by the guidelines. If this happens and
|
||||||
becomes an annoyance, there are a few simple solutions: (1) Maximize the machine acceleration. The planner
|
becomes an annoyance, there are a few simple solutions: (1) Maximize the machine acceleration. The planner
|
||||||
will be able to compute higher velocity profiles within the same combined distance. (2) Maximize line
|
will be able to compute higher velocity profiles within the same combined distance. (2) Maximize line
|
||||||
motion(s) distance per block to a desired tolerance. The more combined distance the planner has to use,
|
motion(s) distance per block to a desired tolerance. The more combined distance the planner has to use,
|
||||||
the faster it can go. (3) Maximize the planner buffer size. This also will increase the combined distance
|
the faster it can go. (3) Maximize the planner buffer size. This also will increase the combined distance
|
||||||
for the planner to compute over. It also increases the number of computations the planner has to perform
|
for the planner to compute over. It also increases the number of computations the planner has to perform
|
||||||
@ -125,14 +123,14 @@ static uint8_t plan_prev_block_index(uint8_t block_index)
|
|||||||
ARM versions should have enough memory and speed for look-ahead blocks numbering up to a hundred or more.
|
ARM versions should have enough memory and speed for look-ahead blocks numbering up to a hundred or more.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
static void planner_recalculate()
|
static void planner_recalculate()
|
||||||
{
|
{
|
||||||
// Initialize block index to the last block in the planner buffer.
|
// Initialize block index to the last block in the planner buffer.
|
||||||
uint8_t block_index = plan_prev_block_index(block_buffer_head);
|
uint8_t block_index = plan_prev_block_index(block_buffer_head);
|
||||||
|
|
||||||
// Bail. Can't do anything with one only one plan-able block.
|
// Bail. Can't do anything with one only one plan-able block.
|
||||||
if (block_index == block_buffer_planned) { return; }
|
if (block_index == block_buffer_planned) { return; }
|
||||||
|
|
||||||
// Reverse Pass: Coarsely maximize all possible deceleration curves back-planning from the last
|
// Reverse Pass: Coarsely maximize all possible deceleration curves back-planning from the last
|
||||||
// block in buffer. Cease planning when the last optimal planned or tail pointer is reached.
|
// block in buffer. Cease planning when the last optimal planned or tail pointer is reached.
|
||||||
// NOTE: Forward pass will later refine and correct the reverse pass to create an optimal plan.
|
// NOTE: Forward pass will later refine and correct the reverse pass to create an optimal plan.
|
||||||
@ -142,19 +140,19 @@ static void planner_recalculate()
|
|||||||
|
|
||||||
// Calculate maximum entry speed for last block in buffer, where the exit speed is always zero.
|
// Calculate maximum entry speed for last block in buffer, where the exit speed is always zero.
|
||||||
current->entry_speed_sqr = min( current->max_entry_speed_sqr, 2*current->acceleration*current->millimeters);
|
current->entry_speed_sqr = min( current->max_entry_speed_sqr, 2*current->acceleration*current->millimeters);
|
||||||
|
|
||||||
block_index = plan_prev_block_index(block_index);
|
block_index = plan_prev_block_index(block_index);
|
||||||
if (block_index == block_buffer_planned) { // Only two plannable blocks in buffer. Reverse pass complete.
|
if (block_index == block_buffer_planned) { // Only two plannable blocks in buffer. Reverse pass complete.
|
||||||
// Check if the first block is the tail. If so, notify stepper to update its current parameters.
|
// Check if the first block is the tail. If so, notify stepper to update its current parameters.
|
||||||
if (block_index == block_buffer_tail) { st_update_plan_block_parameters(); }
|
if (block_index == block_buffer_tail) { st_update_plan_block_parameters(); }
|
||||||
} else { // Three or more plan-able blocks
|
} else { // Three or more plan-able blocks
|
||||||
while (block_index != block_buffer_planned) {
|
while (block_index != block_buffer_planned) {
|
||||||
next = current;
|
next = current;
|
||||||
current = &block_buffer[block_index];
|
current = &block_buffer[block_index];
|
||||||
block_index = plan_prev_block_index(block_index);
|
block_index = plan_prev_block_index(block_index);
|
||||||
|
|
||||||
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
|
// Check if next block is the tail block(=planned block). If so, update current stepper parameters.
|
||||||
if (block_index == block_buffer_tail) { st_update_plan_block_parameters(); }
|
if (block_index == block_buffer_tail) { st_update_plan_block_parameters(); }
|
||||||
|
|
||||||
// Compute maximum entry speed decelerating over the current block from its exit speed.
|
// Compute maximum entry speed decelerating over the current block from its exit speed.
|
||||||
if (current->entry_speed_sqr != current->max_entry_speed_sqr) {
|
if (current->entry_speed_sqr != current->max_entry_speed_sqr) {
|
||||||
@ -166,16 +164,16 @@ static void planner_recalculate()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Forward Pass: Forward plan the acceleration curve from the planned pointer onward.
|
// Forward Pass: Forward plan the acceleration curve from the planned pointer onward.
|
||||||
// Also scans for optimal plan breakpoints and appropriately updates the planned pointer.
|
// Also scans for optimal plan breakpoints and appropriately updates the planned pointer.
|
||||||
next = &block_buffer[block_buffer_planned]; // Begin at buffer planned pointer
|
next = &block_buffer[block_buffer_planned]; // Begin at buffer planned pointer
|
||||||
block_index = plan_next_block_index(block_buffer_planned);
|
block_index = plan_next_block_index(block_buffer_planned);
|
||||||
while (block_index != block_buffer_head) {
|
while (block_index != block_buffer_head) {
|
||||||
current = next;
|
current = next;
|
||||||
next = &block_buffer[block_index];
|
next = &block_buffer[block_index];
|
||||||
|
|
||||||
// Any acceleration detected in the forward pass automatically moves the optimal planned
|
// Any acceleration detected in the forward pass automatically moves the optimal planned
|
||||||
// pointer forward, since everything before this is all optimal. In other words, nothing
|
// pointer forward, since everything before this is all optimal. In other words, nothing
|
||||||
// can improve the plan from the buffer tail to the planned pointer by logic.
|
// can improve the plan from the buffer tail to the planned pointer by logic.
|
||||||
@ -187,20 +185,26 @@ static void planner_recalculate()
|
|||||||
block_buffer_planned = block_index; // Set optimal plan pointer.
|
block_buffer_planned = block_index; // Set optimal plan pointer.
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Any block set at its maximum entry speed also creates an optimal plan up to this
|
// Any block set at its maximum entry speed also creates an optimal plan up to this
|
||||||
// point in the buffer. When the plan is bracketed by either the beginning of the
|
// point in the buffer. When the plan is bracketed by either the beginning of the
|
||||||
// buffer and a maximum entry speed or two maximum entry speeds, every block in between
|
// buffer and a maximum entry speed or two maximum entry speeds, every block in between
|
||||||
// cannot logically be further improved. Hence, we don't have to recompute them anymore.
|
// cannot logically be further improved. Hence, we don't have to recompute them anymore.
|
||||||
if (next->entry_speed_sqr == next->max_entry_speed_sqr) { block_buffer_planned = block_index; }
|
if (next->entry_speed_sqr == next->max_entry_speed_sqr) { block_buffer_planned = block_index; }
|
||||||
block_index = plan_next_block_index( block_index );
|
block_index = plan_next_block_index( block_index );
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void plan_reset()
|
void plan_reset()
|
||||||
{
|
{
|
||||||
memset(&pl, 0, sizeof(planner_t)); // Clear planner struct
|
memset(&pl, 0, sizeof(planner_t)); // Clear planner struct
|
||||||
|
plan_reset_buffer();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void plan_reset_buffer()
|
||||||
|
{
|
||||||
block_buffer_tail = 0;
|
block_buffer_tail = 0;
|
||||||
block_buffer_head = 0; // Empty = tail
|
block_buffer_head = 0; // Empty = tail
|
||||||
next_buffer_head = 1; // plan_next_block_index(block_buffer_head)
|
next_buffer_head = 1; // plan_next_block_index(block_buffer_head)
|
||||||
@ -208,7 +212,7 @@ void plan_reset()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void plan_discard_current_block()
|
void plan_discard_current_block()
|
||||||
{
|
{
|
||||||
if (block_buffer_head != block_buffer_tail) { // Discard non-empty buffer.
|
if (block_buffer_head != block_buffer_tail) { // Discard non-empty buffer.
|
||||||
uint8_t block_index = plan_next_block_index( block_buffer_tail );
|
uint8_t block_index = plan_next_block_index( block_buffer_tail );
|
||||||
@ -219,24 +223,26 @@ void plan_discard_current_block()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
plan_block_t *plan_get_parking_block()
|
// Returns address of planner buffer block used by system motions. Called by segment generator.
|
||||||
|
plan_block_t *plan_get_system_motion_block()
|
||||||
{
|
{
|
||||||
return(&block_buffer[block_buffer_head]);
|
return(&block_buffer[block_buffer_head]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
plan_block_t *plan_get_current_block()
|
// Returns address of first planner block, if available. Called by various main program functions.
|
||||||
|
plan_block_t *plan_get_current_block()
|
||||||
{
|
{
|
||||||
if (block_buffer_head == block_buffer_tail) { return(NULL); } // Buffer empty
|
if (block_buffer_head == block_buffer_tail) { return(NULL); } // Buffer empty
|
||||||
return(&block_buffer[block_buffer_tail]);
|
return(&block_buffer[block_buffer_tail]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
float plan_get_exec_block_exit_speed()
|
float plan_get_exec_block_exit_speed_sqr()
|
||||||
{
|
{
|
||||||
uint8_t block_index = plan_next_block_index(block_buffer_tail);
|
uint8_t block_index = plan_next_block_index(block_buffer_tail);
|
||||||
if (block_index == block_buffer_head) { return( 0.0 ); }
|
if (block_index == block_buffer_head) { return( 0.0 ); }
|
||||||
return( sqrt( block_buffer[block_index].entry_speed_sqr ) );
|
return( block_buffer[block_index].entry_speed_sqr );
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -248,47 +254,89 @@ uint8_t plan_check_full_buffer()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Computes and returns block nominal speed based on running condition and override values.
|
||||||
|
// NOTE: All system motion commands, such as homing/parking, are not subject to overrides.
|
||||||
|
float plan_compute_profile_nominal_speed(plan_block_t *block)
|
||||||
|
{
|
||||||
|
float nominal_speed;
|
||||||
|
if (block->condition & PL_COND_FLAG_RAPID_MOTION) {
|
||||||
|
nominal_speed = block->rapid_rate;
|
||||||
|
nominal_speed *= (0.01*sys.r_override);
|
||||||
|
} else {
|
||||||
|
nominal_speed = block->programmed_rate;
|
||||||
|
if (!(block->condition & PL_COND_FLAG_NO_FEED_OVERRIDE)) { nominal_speed *= (0.01*sys.f_override); }
|
||||||
|
if (nominal_speed > block->rapid_rate) { nominal_speed = block->rapid_rate; }
|
||||||
|
}
|
||||||
|
if (nominal_speed > MINIMUM_FEED_RATE) { return(nominal_speed); }
|
||||||
|
return(MINIMUM_FEED_RATE);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Computes and updates the max entry speed (sqr) of the block, based on the minimum of the junction's
|
||||||
|
// previous and current nominal speeds and max junction speed.
|
||||||
|
static void plan_compute_profile_parameters(plan_block_t *block, float nominal_speed, float prev_nominal_speed)
|
||||||
|
{
|
||||||
|
// Compute the junction maximum entry based on the minimum of the junction speed and neighboring nominal speeds.
|
||||||
|
if (nominal_speed > prev_nominal_speed) { block->max_entry_speed_sqr = prev_nominal_speed*prev_nominal_speed; }
|
||||||
|
else { block->max_entry_speed_sqr = nominal_speed*nominal_speed; }
|
||||||
|
if (block->max_entry_speed_sqr > block->max_junction_speed_sqr) { block->max_entry_speed_sqr = block->max_junction_speed_sqr; }
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Re-calculates buffered motions profile parameters upon a motion-based override change.
|
||||||
|
void plan_update_velocity_profile_parameters()
|
||||||
|
{
|
||||||
|
uint8_t block_index = block_buffer_tail;
|
||||||
|
plan_block_t *block;
|
||||||
|
float nominal_speed;
|
||||||
|
float prev_nominal_speed = SOME_LARGE_VALUE; // Set high for first block nominal speed calculation.
|
||||||
|
while (block_index != block_buffer_head) {
|
||||||
|
block = &block_buffer[block_index];
|
||||||
|
nominal_speed = plan_compute_profile_nominal_speed(block);
|
||||||
|
plan_compute_profile_parameters(block, nominal_speed, prev_nominal_speed);
|
||||||
|
prev_nominal_speed = nominal_speed;
|
||||||
|
block_index = plan_next_block_index(block_index);
|
||||||
|
}
|
||||||
|
pl.previous_nominal_speed = prev_nominal_speed; // Update prev nominal speed for next incoming block.
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
/* Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
|
/* Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
|
||||||
in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed
|
in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed
|
||||||
rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes.
|
rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes.
|
||||||
All position data passed to the planner must be in terms of machine position to keep the planner
|
All position data passed to the planner must be in terms of machine position to keep the planner
|
||||||
independent of any coordinate system changes and offsets, which are handled by the g-code parser.
|
independent of any coordinate system changes and offsets, which are handled by the g-code parser.
|
||||||
NOTE: Assumes buffer is available. Buffer checks are handled at a higher level by motion_control.
|
NOTE: Assumes buffer is available. Buffer checks are handled at a higher level by motion_control.
|
||||||
In other words, the buffer head is never equal to the buffer tail. Also the feed rate input value
|
In other words, the buffer head is never equal to the buffer tail. Also the feed rate input value
|
||||||
is used in three ways: as a normal feed rate if invert_feed_rate is false, as inverse time if
|
is used in three ways: as a normal feed rate if invert_feed_rate is false, as inverse time if
|
||||||
invert_feed_rate is true, or as seek/rapids rate if the feed_rate value is negative (and
|
invert_feed_rate is true, or as seek/rapids rate if the feed_rate value is negative (and
|
||||||
invert_feed_rate always false).
|
invert_feed_rate always false).
|
||||||
The is_parking_motion boolean tells the planner to plan a motion in the always unused block buffer
|
The system motion condition tells the planner to plan a motion in the always unused block buffer
|
||||||
head. It avoids changing the planner state and preserves the buffer to ensure subsequent gcode
|
head. It avoids changing the planner state and preserves the buffer to ensure subsequent gcode
|
||||||
motions are still planned correctly, while the stepper module only points to the block buffer head
|
motions are still planned correctly, while the stepper module only points to the block buffer head
|
||||||
to execute the parking motion. */
|
to execute the special system motion. */
|
||||||
#ifdef USE_LINE_NUMBERS
|
uint8_t plan_buffer_line(float *target, plan_line_data_t *pl_data)
|
||||||
uint8_t plan_buffer_line(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_parking_motion, int32_t line_number)
|
|
||||||
#else
|
|
||||||
uint8_t plan_buffer_line(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_parking_motion)
|
|
||||||
#endif
|
|
||||||
{
|
{
|
||||||
// Prepare and initialize new block
|
// Prepare and initialize new block. Copy relevant pl_data for block execution.
|
||||||
plan_block_t *block = &block_buffer[block_buffer_head];
|
plan_block_t *block = &block_buffer[block_buffer_head];
|
||||||
block->step_event_count = 0;
|
memset(block,0,sizeof(plan_block_t)); // Zero all block values.
|
||||||
block->millimeters = 0;
|
block->condition = pl_data->condition;
|
||||||
block->direction_bits = 0;
|
#ifdef VARIABLE_SPINDLE
|
||||||
block->acceleration = SOME_LARGE_VALUE; // Scaled down to maximum acceleration later
|
block->spindle_speed = pl_data->spindle_speed;
|
||||||
|
#endif
|
||||||
#ifdef USE_LINE_NUMBERS
|
#ifdef USE_LINE_NUMBERS
|
||||||
block->line_number = line_number;
|
block->line_number = pl_data->line_number;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Compute and store initial move distance data.
|
// Compute and store initial move distance data.
|
||||||
// TODO: After this for-loop, we don't touch the stepper algorithm data. Might be a good idea
|
|
||||||
// to try to keep these types of things completely separate from the planner for portability.
|
|
||||||
int32_t target_steps[N_AXIS], position_steps[N_AXIS];
|
int32_t target_steps[N_AXIS], position_steps[N_AXIS];
|
||||||
float unit_vec[N_AXIS], delta_mm;
|
float unit_vec[N_AXIS], delta_mm;
|
||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
|
|
||||||
// Copy position data based on type of motion being planned.
|
// Copy position data based on type of motion being planned.
|
||||||
if (is_parking_motion) { memcpy(position_steps, sys.position, sizeof(sys.position)); }
|
if (block->condition & PL_COND_FLAG_SYSTEM_MOTION) { memcpy(position_steps, sys_position, sizeof(sys_position)); }
|
||||||
else { memcpy(position_steps, pl.position, sizeof(pl.position)); }
|
else { memcpy(position_steps, pl.position, sizeof(pl.position)); }
|
||||||
|
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
target_steps[A_MOTOR] = lround(target[A_MOTOR]*settings.steps_per_mm[A_MOTOR]);
|
target_steps[A_MOTOR] = lround(target[A_MOTOR]*settings.steps_per_mm[A_MOTOR]);
|
||||||
target_steps[B_MOTOR] = lround(target[B_MOTOR]*settings.steps_per_mm[B_MOTOR]);
|
target_steps[B_MOTOR] = lround(target[B_MOTOR]*settings.steps_per_mm[B_MOTOR]);
|
||||||
@ -307,9 +355,9 @@ uint8_t plan_check_full_buffer()
|
|||||||
}
|
}
|
||||||
block->step_event_count = max(block->step_event_count, block->steps[idx]);
|
block->step_event_count = max(block->step_event_count, block->steps[idx]);
|
||||||
if (idx == A_MOTOR) {
|
if (idx == A_MOTOR) {
|
||||||
delta_mm = ((target_steps[X_AXIS]-position_steps[X_AXIS]) + (target_steps[Y_AXIS]-position_steps[Y_AXIS]))/settings.steps_per_mm[idx];
|
delta_mm = (target_steps[X_AXIS]-position_steps[X_AXIS] + target_steps[Y_AXIS]-position_steps[Y_AXIS])/settings.steps_per_mm[idx];
|
||||||
} else if (idx == B_MOTOR) {
|
} else if (idx == B_MOTOR) {
|
||||||
delta_mm = ((target_steps[X_AXIS]-position_steps[X_AXIS]) - (target_steps[Y_AXIS]-position_steps[Y_AXIS]))/settings.steps_per_mm[idx];
|
delta_mm = (target_steps[X_AXIS]-position_steps[X_AXIS] - target_steps[Y_AXIS]+position_steps[Y_AXIS])/settings.steps_per_mm[idx];
|
||||||
} else {
|
} else {
|
||||||
delta_mm = (target_steps[idx] - position_steps[idx])/settings.steps_per_mm[idx];
|
delta_mm = (target_steps[idx] - position_steps[idx])/settings.steps_per_mm[idx];
|
||||||
}
|
}
|
||||||
@ -319,116 +367,97 @@ uint8_t plan_check_full_buffer()
|
|||||||
block->step_event_count = max(block->step_event_count, block->steps[idx]);
|
block->step_event_count = max(block->step_event_count, block->steps[idx]);
|
||||||
delta_mm = (target_steps[idx] - position_steps[idx])/settings.steps_per_mm[idx];
|
delta_mm = (target_steps[idx] - position_steps[idx])/settings.steps_per_mm[idx];
|
||||||
#endif
|
#endif
|
||||||
unit_vec[idx] = delta_mm; // Store unit vector numerator. Denominator computed later.
|
unit_vec[idx] = delta_mm; // Store unit vector numerator
|
||||||
|
|
||||||
// Set direction bits. Bit enabled always means direction is negative.
|
|
||||||
if (delta_mm < 0 ) { block->direction_bits |= get_direction_pin_mask(idx); }
|
|
||||||
|
|
||||||
// Incrementally compute total move distance by Euclidean norm. First add square of each term.
|
|
||||||
block->millimeters += delta_mm*delta_mm;
|
|
||||||
}
|
|
||||||
block->millimeters = sqrt(block->millimeters); // Complete millimeters calculation with sqrt()
|
|
||||||
|
|
||||||
// Bail if this is a zero-length block. Highly unlikely to occur.
|
|
||||||
if (block->step_event_count == 0) { return(PLAN_EMPTY_BLOCK); }
|
|
||||||
|
|
||||||
// Adjust feed_rate value to mm/min depending on type of rate input (normal, inverse time, or rapids)
|
|
||||||
// TODO: Need to distinguish a rapids vs feed move for overrides. Some flag of some sort.
|
|
||||||
if (feed_rate < 0) { feed_rate = SOME_LARGE_VALUE; } // Scaled down to absolute max/rapids rate later
|
|
||||||
else if (invert_feed_rate) { feed_rate *= block->millimeters; }
|
|
||||||
if (feed_rate < MINIMUM_FEED_RATE) { feed_rate = MINIMUM_FEED_RATE; } // Prevents step generation round-off condition.
|
|
||||||
|
|
||||||
// Calculate the unit vector of the line move and the block maximum feed rate and acceleration scaled
|
// Set direction bits. Bit enabled always means direction is negative.
|
||||||
// down such that no individual axes maximum values are exceeded with respect to the line direction.
|
if (delta_mm < 0.0 ) { block->direction_bits |= get_direction_pin_mask(idx); }
|
||||||
|
}
|
||||||
|
|
||||||
|
// Bail if this is a zero-length block. Highly unlikely to occur.
|
||||||
|
if (block->step_event_count == 0) { return(PLAN_EMPTY_BLOCK); }
|
||||||
|
|
||||||
|
// Calculate the unit vector of the line move and the block maximum feed rate and acceleration scaled
|
||||||
|
// down such that no individual axes maximum values are exceeded with respect to the line direction.
|
||||||
// NOTE: This calculation assumes all axes are orthogonal (Cartesian) and works with ABC-axes,
|
// NOTE: This calculation assumes all axes are orthogonal (Cartesian) and works with ABC-axes,
|
||||||
// if they are also orthogonal/independent. Operates on the absolute value of the unit vector.
|
// if they are also orthogonal/independent. Operates on the absolute value of the unit vector.
|
||||||
float inverse_unit_vec_value;
|
block->millimeters = convert_delta_vector_to_unit_vector(unit_vec);
|
||||||
float inverse_millimeters = 1.0/block->millimeters; // Inverse millimeters to remove multiple float divides
|
block->acceleration = limit_value_by_axis_maximum(settings.acceleration, unit_vec);
|
||||||
float junction_cos_theta = 0.0;
|
block->rapid_rate = limit_value_by_axis_maximum(settings.max_rate, unit_vec);
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
|
||||||
if (unit_vec[idx] != 0) { // Avoid divide by zero.
|
|
||||||
unit_vec[idx] *= inverse_millimeters; // Complete unit vector calculation
|
|
||||||
inverse_unit_vec_value = fabs(1.0/unit_vec[idx]); // Inverse to remove multiple float divides.
|
|
||||||
|
|
||||||
// Check and limit feed rate against max individual axis velocities and accelerations
|
// Store programmed rate.
|
||||||
feed_rate = min(feed_rate,settings.max_rate[idx]*inverse_unit_vec_value);
|
block->programmed_rate = pl_data->feed_rate;
|
||||||
block->acceleration = min(block->acceleration,settings.acceleration[idx]*inverse_unit_vec_value);
|
if (block->condition & PL_COND_FLAG_INVERSE_TIME) { block->programmed_rate *= block->millimeters; }
|
||||||
|
|
||||||
// Incrementally compute cosine of angle between previous and current path. Cos(theta) of the junction
|
|
||||||
// between the current move and the previous move is simply the dot product of the two unit vectors,
|
|
||||||
// where prev_unit_vec is negative. Used later to compute maximum junction speed.
|
|
||||||
junction_cos_theta -= pl.previous_unit_vec[idx] * unit_vec[idx];
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// TODO: Need to check this method handling zero junction speeds when starting from rest.
|
// TODO: Need to check this method handling zero junction speeds when starting from rest.
|
||||||
if ((block_buffer_head == block_buffer_tail) || is_parking_motion) {
|
if ((block_buffer_head == block_buffer_tail) || (block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||||
|
|
||||||
// Initialize block entry speed as zero. Assume it will be starting from rest. Planner will correct this later.
|
// Initialize block entry speed as zero. Assume it will be starting from rest. Planner will correct this later.
|
||||||
// If parking motion, the parking block always is assumed to start from rest and end at a complete stop.
|
// If system motion, the system motion block always is assumed to start from rest and end at a complete stop.
|
||||||
block->entry_speed_sqr = 0.0;
|
block->entry_speed_sqr = 0.0;
|
||||||
block->max_junction_speed_sqr = 0.0; // Starting from rest. Enforce start from zero velocity.
|
block->max_junction_speed_sqr = 0.0; // Starting from rest. Enforce start from zero velocity.
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
/*
|
// Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
|
||||||
Compute maximum allowable entry speed at junction by centripetal acceleration approximation.
|
// Let a circle be tangent to both previous and current path line segments, where the junction
|
||||||
Let a circle be tangent to both previous and current path line segments, where the junction
|
// deviation is defined as the distance from the junction to the closest edge of the circle,
|
||||||
deviation is defined as the distance from the junction to the closest edge of the circle,
|
// colinear with the circle center. The circular segment joining the two paths represents the
|
||||||
colinear with the circle center. The circular segment joining the two paths represents the
|
// path of centripetal acceleration. Solve for max velocity based on max acceleration about the
|
||||||
path of centripetal acceleration. Solve for max velocity based on max acceleration about the
|
// radius of the circle, defined indirectly by junction deviation. This may be also viewed as
|
||||||
radius of the circle, defined indirectly by junction deviation. This may be also viewed as
|
// path width or max_jerk in the previous Grbl version. This approach does not actually deviate
|
||||||
path width or max_jerk in the previous Grbl version. This approach does not actually deviate
|
// from path, but used as a robust way to compute cornering speeds, as it takes into account the
|
||||||
from path, but used as a robust way to compute cornering speeds, as it takes into account the
|
// nonlinearities of both the junction angle and junction velocity.
|
||||||
nonlinearities of both the junction angle and junction velocity.
|
//
|
||||||
|
// NOTE: If the junction deviation value is finite, Grbl executes the motions in an exact path
|
||||||
|
// mode (G61). If the junction deviation value is zero, Grbl will execute the motion in an exact
|
||||||
|
// stop mode (G61.1) manner. In the future, if continuous mode (G64) is desired, the math here
|
||||||
|
// is exactly the same. Instead of motioning all the way to junction point, the machine will
|
||||||
|
// just follow the arc circle defined here. The Arduino doesn't have the CPU cycles to perform
|
||||||
|
// a continuous mode path, but ARM-based microcontrollers most certainly do.
|
||||||
|
//
|
||||||
|
// NOTE: The max junction speed is a fixed value, since machine acceleration limits cannot be
|
||||||
|
// changed dynamically during operation nor can the line move geometry. This must be kept in
|
||||||
|
// memory in the event of a feedrate override changing the nominal speeds of blocks, which can
|
||||||
|
// change the overall maximum entry speed conditions of all blocks.
|
||||||
|
|
||||||
|
float junction_unit_vec[N_AXIS];
|
||||||
|
float junction_cos_theta = 0.0;
|
||||||
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
|
junction_cos_theta -= pl.previous_unit_vec[idx]*unit_vec[idx];
|
||||||
|
junction_unit_vec[idx] = unit_vec[idx]-pl.previous_unit_vec[idx];
|
||||||
|
}
|
||||||
|
|
||||||
NOTE: If the junction deviation value is finite, Grbl executes the motions in an exact path
|
|
||||||
mode (G61). If the junction deviation value is zero, Grbl will execute the motion in an exact
|
|
||||||
stop mode (G61.1) manner. In the future, if continuous mode (G64) is desired, the math here
|
|
||||||
is exactly the same. Instead of motioning all the way to junction point, the machine will
|
|
||||||
just follow the arc circle defined here. The Arduino doesn't have the CPU cycles to perform
|
|
||||||
a continuous mode path, but ARM-based microcontrollers most certainly do.
|
|
||||||
|
|
||||||
NOTE: The max junction speed is a fixed value, since machine acceleration limits cannot be
|
|
||||||
changed dynamically during operation nor can the line move geometry. This must be kept in
|
|
||||||
memory in the event of a feedrate override changing the nominal speeds of blocks, which can
|
|
||||||
change the overall maximum entry speed conditions of all blocks.
|
|
||||||
*/
|
|
||||||
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
|
// NOTE: Computed without any expensive trig, sin() or acos(), by trig half angle identity of cos(theta).
|
||||||
if (junction_cos_theta > 0.999999) {
|
if (junction_cos_theta > 0.999999) {
|
||||||
// For a 0 degree acute junction, just set minimum junction speed.
|
// For a 0 degree acute junction, just set minimum junction speed.
|
||||||
block->max_junction_speed_sqr = MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED;
|
block->max_junction_speed_sqr = MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED;
|
||||||
} else {
|
} else {
|
||||||
junction_cos_theta = max(junction_cos_theta,-0.999999); // Check for numerical round-off to avoid divide by zero.
|
if (junction_cos_theta < -0.999999) {
|
||||||
float sin_theta_d2 = sqrt(0.5*(1.0-junction_cos_theta)); // Trig half angle identity. Always positive.
|
// Junction is a straight line or 180 degrees. Junction speed is infinite.
|
||||||
|
block->max_junction_speed_sqr = SOME_LARGE_VALUE;
|
||||||
// TODO: Technically, the acceleration used in calculation needs to be limited by the minimum of the
|
} else {
|
||||||
// two junctions. However, this shouldn't be a significant problem except in extreme circumstances.
|
convert_delta_vector_to_unit_vector(junction_unit_vec);
|
||||||
block->max_junction_speed_sqr = max( MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED,
|
float junction_acceleration = limit_value_by_axis_maximum(settings.acceleration, junction_unit_vec);
|
||||||
(block->acceleration * settings.junction_deviation * sin_theta_d2)/(1.0-sin_theta_d2) );
|
float sin_theta_d2 = sqrt(0.5*(1.0-junction_cos_theta)); // Trig half angle identity. Always positive.
|
||||||
|
block->max_junction_speed_sqr = max( MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED,
|
||||||
|
(junction_acceleration * settings.junction_deviation * sin_theta_d2)/(1.0-sin_theta_d2) );
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Store block nominal speed
|
|
||||||
block->nominal_speed_sqr = feed_rate*feed_rate; // (mm/min). Always > 0
|
|
||||||
|
|
||||||
// Compute the junction maximum entry based on the minimum of the junction speed and neighboring nominal speeds.
|
|
||||||
block->max_entry_speed_sqr = min(block->max_junction_speed_sqr,
|
|
||||||
min(block->nominal_speed_sqr,pl.previous_nominal_speed_sqr));
|
|
||||||
|
|
||||||
// Block parking motion from updating this data to ensure next g-code motion is computed correctly.
|
// Block system motion from updating this data to ensure next g-code motion is computed correctly.
|
||||||
if (!is_parking_motion) {
|
if (!(block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
|
||||||
// Update previous path unit_vector and nominal speed (squared)
|
float nominal_speed = plan_compute_profile_nominal_speed(block);
|
||||||
|
plan_compute_profile_parameters(block, nominal_speed, pl.previous_nominal_speed);
|
||||||
|
pl.previous_nominal_speed = nominal_speed;
|
||||||
|
|
||||||
|
// Update previous path unit_vector and planner position.
|
||||||
memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
|
memcpy(pl.previous_unit_vec, unit_vec, sizeof(unit_vec)); // pl.previous_unit_vec[] = unit_vec[]
|
||||||
pl.previous_nominal_speed_sqr = block->nominal_speed_sqr;
|
|
||||||
|
|
||||||
// Update planner position
|
|
||||||
memcpy(pl.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[]
|
memcpy(pl.position, target_steps, sizeof(target_steps)); // pl.position[] = target_steps[]
|
||||||
|
|
||||||
// New block is all set. Update buffer head and next buffer head indices.
|
// New block is all set. Update buffer head and next buffer head indices.
|
||||||
block_buffer_head = next_buffer_head;
|
block_buffer_head = next_buffer_head;
|
||||||
next_buffer_head = plan_next_block_index(block_buffer_head);
|
next_buffer_head = plan_next_block_index(block_buffer_head);
|
||||||
|
|
||||||
// Finish up by recalculating the plan with the new block.
|
// Finish up by recalculating the plan with the new block.
|
||||||
planner_recalculate();
|
planner_recalculate();
|
||||||
}
|
}
|
||||||
@ -440,25 +469,34 @@ uint8_t plan_check_full_buffer()
|
|||||||
void plan_sync_position()
|
void plan_sync_position()
|
||||||
{
|
{
|
||||||
// TODO: For motor configurations not in the same coordinate frame as the machine position,
|
// TODO: For motor configurations not in the same coordinate frame as the machine position,
|
||||||
// this function needs to be updated to accomodate the difference.
|
// this function needs to be updated to accomodate the difference.
|
||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
if (idx==A_MOTOR) {
|
if (idx==X_AXIS) {
|
||||||
pl.position[idx] = (sys.position[A_MOTOR] + sys.position[B_MOTOR])/2;
|
pl.position[X_AXIS] = system_convert_corexy_to_x_axis_steps(sys_position);
|
||||||
} else if (idx==B_MOTOR) {
|
} else if (idx==Y_AXIS) {
|
||||||
pl.position[idx] = (sys.position[A_MOTOR] - sys.position[B_MOTOR])/2;
|
pl.position[Y_AXIS] = system_convert_corexy_to_y_axis_steps(sys_position);
|
||||||
} else {
|
} else {
|
||||||
pl.position[idx] = sys.position[idx];
|
pl.position[idx] = sys_position[idx];
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
pl.position[idx] = sys.position[idx];
|
pl.position[idx] = sys_position[idx];
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Returns the number of available blocks are in the planner buffer.
|
||||||
|
uint8_t plan_get_block_buffer_available()
|
||||||
|
{
|
||||||
|
if (block_buffer_head >= block_buffer_tail) { return((BLOCK_BUFFER_SIZE-1)-(block_buffer_head-block_buffer_tail)); }
|
||||||
|
return((block_buffer_tail-block_buffer_head-1));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// Returns the number of active blocks are in the planner buffer.
|
// Returns the number of active blocks are in the planner buffer.
|
||||||
|
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h
|
||||||
uint8_t plan_get_block_buffer_count()
|
uint8_t plan_get_block_buffer_count()
|
||||||
{
|
{
|
||||||
if (block_buffer_head >= block_buffer_tail) { return(block_buffer_head-block_buffer_tail); }
|
if (block_buffer_head >= block_buffer_tail) { return(block_buffer_head-block_buffer_tail); }
|
||||||
@ -473,5 +511,5 @@ void plan_cycle_reinitialize()
|
|||||||
// Re-plan from a complete stop. Reset planner entry speeds and buffer planned pointer.
|
// Re-plan from a complete stop. Reset planner entry speeds and buffer planned pointer.
|
||||||
st_update_plan_block_parameters();
|
st_update_plan_block_parameters();
|
||||||
block_buffer_planned = block_buffer_tail;
|
block_buffer_planned = block_buffer_tail;
|
||||||
planner_recalculate();
|
planner_recalculate();
|
||||||
}
|
}
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
planner.h - buffers movement commands and manages the acceleration profile plan
|
planner.h - buffers movement commands and manages the acceleration profile plan
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -26,59 +26,89 @@
|
|||||||
// The number of linear motions that can be in the plan at any give time
|
// The number of linear motions that can be in the plan at any give time
|
||||||
#ifndef BLOCK_BUFFER_SIZE
|
#ifndef BLOCK_BUFFER_SIZE
|
||||||
#ifdef USE_LINE_NUMBERS
|
#ifdef USE_LINE_NUMBERS
|
||||||
#define BLOCK_BUFFER_SIZE 16
|
#define BLOCK_BUFFER_SIZE 15
|
||||||
#else
|
#else
|
||||||
#define BLOCK_BUFFER_SIZE 18
|
#define BLOCK_BUFFER_SIZE 17
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Returned status message from planner.
|
||||||
#define PLAN_OK true
|
#define PLAN_OK true
|
||||||
#define PLAN_EMPTY_BLOCK false
|
#define PLAN_EMPTY_BLOCK false
|
||||||
|
|
||||||
|
// Define planner data condition flags. Used to denote running conditions of a block.
|
||||||
|
#define PL_COND_FLAG_RAPID_MOTION bit(0)
|
||||||
|
#define PL_COND_FLAG_SYSTEM_MOTION bit(1) // Single motion. Circumvents planner state. Used by home/park.
|
||||||
|
#define PL_COND_FLAG_NO_FEED_OVERRIDE bit(2) // Motion does not honor feed override.
|
||||||
|
#define PL_COND_FLAG_INVERSE_TIME bit(3)
|
||||||
|
#define PL_COND_FLAG_SPINDLE_CW bit(4)
|
||||||
|
#define PL_COND_FLAG_SPINDLE_CCW bit(5)
|
||||||
|
#define PL_COND_FLAG_COOLANT_FLOOD bit(6)
|
||||||
|
#define PL_COND_FLAG_COOLANT_MIST bit(7)
|
||||||
|
|
||||||
|
|
||||||
// This struct stores a linear movement of a g-code block motion with its critical "nominal" values
|
// This struct stores a linear movement of a g-code block motion with its critical "nominal" values
|
||||||
// are as specified in the source g-code.
|
// are as specified in the source g-code.
|
||||||
typedef struct {
|
typedef struct {
|
||||||
// Fields used by the bresenham algorithm for tracing the line
|
// Fields used by the bresenham algorithm for tracing the line
|
||||||
// NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values.
|
// NOTE: Used by stepper algorithm to execute the block correctly. Do not alter these values.
|
||||||
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
|
|
||||||
uint32_t steps[N_AXIS]; // Step count along each axis
|
uint32_t steps[N_AXIS]; // Step count along each axis
|
||||||
uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block.
|
uint32_t step_event_count; // The maximum step axis count and number of steps required to complete this block.
|
||||||
|
uint8_t direction_bits; // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
|
||||||
|
|
||||||
|
// Block condition data to ensure correct execution depending on states and overrides.
|
||||||
|
uint8_t condition; // Block bitflag variable defining block run conditions. Copied from pl_line_data.
|
||||||
|
#ifdef USE_LINE_NUMBERS
|
||||||
|
int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data.
|
||||||
|
#endif
|
||||||
|
|
||||||
// Fields used by the motion planner to manage acceleration. Some of these values may be updated
|
// Fields used by the motion planner to manage acceleration. Some of these values may be updated
|
||||||
// by the stepper module during execution of special motion cases for replanning purposes.
|
// by the stepper module during execution of special motion cases for replanning purposes.
|
||||||
float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2
|
float entry_speed_sqr; // The current planned entry speed at block junction in (mm/min)^2
|
||||||
float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and
|
float max_entry_speed_sqr; // Maximum allowable entry speed based on the minimum of junction limit and
|
||||||
// neighboring nominal speeds with overrides in (mm/min)^2
|
// neighboring nominal speeds with overrides in (mm/min)^2
|
||||||
float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2
|
float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2). Does not change.
|
||||||
float nominal_speed_sqr; // Axis-limit adjusted nominal speed for this block in (mm/min)^2
|
float millimeters; // The remaining distance for this block to be executed in (mm).
|
||||||
float acceleration; // Axis-limit adjusted line acceleration in (mm/min^2)
|
// NOTE: This value may be altered by stepper algorithm during execution.
|
||||||
float millimeters; // The remaining distance for this block to be executed in (mm)
|
|
||||||
// uint8_t max_override; // Maximum override value based on axis speed limits
|
|
||||||
|
|
||||||
#ifdef USE_LINE_NUMBERS
|
// Stored rate limiting data used by planner when changes occur.
|
||||||
int32_t line_number;
|
float max_junction_speed_sqr; // Junction entry speed limit based on direction vectors in (mm/min)^2
|
||||||
|
float rapid_rate; // Axis-limit adjusted maximum rate for this block direction in (mm/min)
|
||||||
|
float programmed_rate; // Programmed rate of this block (mm/min).
|
||||||
|
|
||||||
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
// Stored spindle speed data used by spindle overrides and resuming methods.
|
||||||
|
float spindle_speed; // Block spindle speed. Copied from pl_line_data.
|
||||||
#endif
|
#endif
|
||||||
} plan_block_t;
|
} plan_block_t;
|
||||||
|
|
||||||
|
|
||||||
// Initialize and reset the motion plan subsystem
|
|
||||||
void plan_reset();
|
|
||||||
|
|
||||||
// Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
|
// Planner data prototype. Must be used when passing new motions to the planner.
|
||||||
|
typedef struct {
|
||||||
|
float feed_rate; // Desired feed rate for line motion. Value is ignored, if rapid motion.
|
||||||
|
float spindle_speed; // Desired spindle speed through line motion.
|
||||||
|
uint8_t condition; // Bitflag variable to indicate planner conditions. See defines above.
|
||||||
|
#ifdef USE_LINE_NUMBERS
|
||||||
|
int32_t line_number; // Desired line number to report when executing.
|
||||||
|
#endif
|
||||||
|
} plan_line_data_t;
|
||||||
|
|
||||||
|
|
||||||
|
// Initialize and reset the motion plan subsystem
|
||||||
|
void plan_reset(); // Reset all
|
||||||
|
void plan_reset_buffer(); // Reset buffer only.
|
||||||
|
|
||||||
|
// Add a new linear movement to the buffer. target[N_AXIS] is the signed, absolute target position
|
||||||
// in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed
|
// in millimeters. Feed rate specifies the speed of the motion. If feed rate is inverted, the feed
|
||||||
// rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes.
|
// rate is taken to mean "frequency" and would complete the operation in 1/feed_rate minutes.
|
||||||
#ifdef USE_LINE_NUMBERS
|
uint8_t plan_buffer_line(float *target, plan_line_data_t *pl_data);
|
||||||
uint8_t plan_buffer_line(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_parking_motion, int32_t line_number);
|
|
||||||
#else
|
|
||||||
uint8_t plan_buffer_line(float *target, float feed_rate, uint8_t invert_feed_rate, uint8_t is_parking_motion);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Called when the current block is no longer needed. Discards the block and makes the memory
|
// Called when the current block is no longer needed. Discards the block and makes the memory
|
||||||
// availible for new blocks.
|
// availible for new blocks.
|
||||||
void plan_discard_current_block();
|
void plan_discard_current_block();
|
||||||
|
|
||||||
// Gets the planner block for the parking special motion case. Parking uses the always available buffer head.
|
// Gets the planner block for the special system motion cases. (Parking/Homing)
|
||||||
plan_block_t *plan_get_parking_block();
|
plan_block_t *plan_get_system_motion_block();
|
||||||
|
|
||||||
// Gets the current block. Returns NULL if buffer empty
|
// Gets the current block. Returns NULL if buffer empty
|
||||||
plan_block_t *plan_get_current_block();
|
plan_block_t *plan_get_current_block();
|
||||||
@ -87,7 +117,13 @@ plan_block_t *plan_get_current_block();
|
|||||||
uint8_t plan_next_block_index(uint8_t block_index);
|
uint8_t plan_next_block_index(uint8_t block_index);
|
||||||
|
|
||||||
// Called by step segment buffer when computing executing block velocity profile.
|
// Called by step segment buffer when computing executing block velocity profile.
|
||||||
float plan_get_exec_block_exit_speed();
|
float plan_get_exec_block_exit_speed_sqr();
|
||||||
|
|
||||||
|
// Called by main program during planner calculations and step segment buffer during initialization.
|
||||||
|
float plan_compute_profile_nominal_speed(plan_block_t *block);
|
||||||
|
|
||||||
|
// Re-calculates buffered motions profile parameters upon a motion-based override change.
|
||||||
|
void plan_update_velocity_profile_parameters();
|
||||||
|
|
||||||
// Reset the planner position vector (in steps)
|
// Reset the planner position vector (in steps)
|
||||||
void plan_sync_position();
|
void plan_sync_position();
|
||||||
@ -95,10 +131,17 @@ void plan_sync_position();
|
|||||||
// Reinitialize plan with a partially completed block
|
// Reinitialize plan with a partially completed block
|
||||||
void plan_cycle_reinitialize();
|
void plan_cycle_reinitialize();
|
||||||
|
|
||||||
|
// Returns the number of available blocks are in the planner buffer.
|
||||||
|
uint8_t plan_get_block_buffer_available();
|
||||||
|
|
||||||
// Returns the number of active blocks are in the planner buffer.
|
// Returns the number of active blocks are in the planner buffer.
|
||||||
|
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h
|
||||||
uint8_t plan_get_block_buffer_count();
|
uint8_t plan_get_block_buffer_count();
|
||||||
|
|
||||||
// Returns the status of the block ring buffer. True, if buffer is full.
|
// Returns the status of the block ring buffer. True, if buffer is full.
|
||||||
uint8_t plan_check_full_buffer();
|
uint8_t plan_check_full_buffer();
|
||||||
|
|
||||||
|
void plan_get_planner_mpos(float *target);
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
104
grbl/print.c
104
grbl/print.c
@ -2,7 +2,7 @@
|
|||||||
print.c - Functions for formatting output strings
|
print.c - Functions for formatting output strings
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -39,20 +39,20 @@ void printPgmString(const char *s)
|
|||||||
|
|
||||||
|
|
||||||
// void printIntegerInBase(unsigned long n, unsigned long base)
|
// void printIntegerInBase(unsigned long n, unsigned long base)
|
||||||
// {
|
// {
|
||||||
// unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
|
// unsigned char buf[8 * sizeof(long)]; // Assumes 8-bit chars.
|
||||||
// unsigned long i = 0;
|
// unsigned long i = 0;
|
||||||
//
|
//
|
||||||
// if (n == 0) {
|
// if (n == 0) {
|
||||||
// serial_write('0');
|
// serial_write('0');
|
||||||
// return;
|
// return;
|
||||||
// }
|
// }
|
||||||
//
|
//
|
||||||
// while (n > 0) {
|
// while (n > 0) {
|
||||||
// buf[i++] = n % base;
|
// buf[i++] = n % base;
|
||||||
// n /= base;
|
// n /= base;
|
||||||
// }
|
// }
|
||||||
//
|
//
|
||||||
// for (; i > 0; i--)
|
// for (; i > 0; i--)
|
||||||
// serial_write(buf[i - 1] < 10 ?
|
// serial_write(buf[i - 1] < 10 ?
|
||||||
// '0' + buf[i - 1] :
|
// '0' + buf[i - 1] :
|
||||||
@ -60,15 +60,33 @@ void printPgmString(const char *s)
|
|||||||
// }
|
// }
|
||||||
|
|
||||||
|
|
||||||
// Prints an uint8 variable with base and number of desired digits.
|
// Prints an uint8 variable in base 10.
|
||||||
void print_unsigned_int8(uint8_t n, uint8_t base, uint8_t digits)
|
void print_uint8_base10(uint8_t n)
|
||||||
{
|
{
|
||||||
|
uint8_t digit_a = 0;
|
||||||
|
uint8_t digit_b = 0;
|
||||||
|
if (n >= 100) { // 100-255
|
||||||
|
digit_a = '0' + n % 10;
|
||||||
|
n /= 10;
|
||||||
|
}
|
||||||
|
if (n >= 10) { // 10-99
|
||||||
|
digit_b = '0' + n % 10;
|
||||||
|
n /= 10;
|
||||||
|
}
|
||||||
|
serial_write('0' + n);
|
||||||
|
if (digit_b) { serial_write(digit_b); }
|
||||||
|
if (digit_a) { serial_write(digit_a); }
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Prints an uint8 variable in base 2 with desired number of desired digits.
|
||||||
|
void print_uint8_base2_ndigit(uint8_t n, uint8_t digits) {
|
||||||
unsigned char buf[digits];
|
unsigned char buf[digits];
|
||||||
uint8_t i = 0;
|
uint8_t i = 0;
|
||||||
|
|
||||||
for (; i < digits; i++) {
|
for (; i < digits; i++) {
|
||||||
buf[i] = n % base ;
|
buf[i] = n % 2 ;
|
||||||
n /= base;
|
n /= 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (; i > 0; i--)
|
for (; i > 0; i--)
|
||||||
@ -76,38 +94,21 @@ void print_unsigned_int8(uint8_t n, uint8_t base, uint8_t digits)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Prints an uint8 variable in base 2.
|
|
||||||
void print_uint8_base2(uint8_t n) {
|
|
||||||
print_unsigned_int8(n,2,8);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// Prints an uint8 variable in base 10.
|
|
||||||
void print_uint8_base10(uint8_t n)
|
|
||||||
{
|
|
||||||
uint8_t digits;
|
|
||||||
if (n < 10) { digits = 1; }
|
|
||||||
else if (n < 100) { digits = 2; }
|
|
||||||
else { digits = 3; }
|
|
||||||
print_unsigned_int8(n,10,digits);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
void print_uint32_base10(uint32_t n)
|
void print_uint32_base10(uint32_t n)
|
||||||
{
|
{
|
||||||
if (n == 0) {
|
if (n == 0) {
|
||||||
serial_write('0');
|
serial_write('0');
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
unsigned char buf[10];
|
||||||
|
uint8_t i = 0;
|
||||||
|
|
||||||
unsigned char buf[10];
|
|
||||||
uint8_t i = 0;
|
|
||||||
|
|
||||||
while (n > 0) {
|
while (n > 0) {
|
||||||
buf[i++] = n % 10;
|
buf[i++] = n % 10;
|
||||||
n /= 10;
|
n /= 10;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (; i > 0; i--)
|
for (; i > 0; i--)
|
||||||
serial_write('0' + buf[i-1]);
|
serial_write('0' + buf[i-1]);
|
||||||
}
|
}
|
||||||
@ -127,7 +128,7 @@ void printInteger(long n)
|
|||||||
// Convert float to string by immediately converting to a long integer, which contains
|
// Convert float to string by immediately converting to a long integer, which contains
|
||||||
// more digits than a float. Number of decimal places, which are tracked by a counter,
|
// more digits than a float. Number of decimal places, which are tracked by a counter,
|
||||||
// may be set by the user. The integer is then efficiently converted to a string.
|
// may be set by the user. The integer is then efficiently converted to a string.
|
||||||
// NOTE: AVR '%' and '/' integer operations are very efficient. Bitshifting speed-up
|
// NOTE: AVR '%' and '/' integer operations are very efficient. Bitshifting speed-up
|
||||||
// techniques are actually just slightly slower. Found this out the hard way.
|
// techniques are actually just slightly slower. Found this out the hard way.
|
||||||
void printFloat(float n, uint8_t decimal_places)
|
void printFloat(float n, uint8_t decimal_places)
|
||||||
{
|
{
|
||||||
@ -143,25 +144,25 @@ void printFloat(float n, uint8_t decimal_places)
|
|||||||
}
|
}
|
||||||
if (decimals) { n *= 10; }
|
if (decimals) { n *= 10; }
|
||||||
n += 0.5; // Add rounding factor. Ensures carryover through entire value.
|
n += 0.5; // Add rounding factor. Ensures carryover through entire value.
|
||||||
|
|
||||||
// Generate digits backwards and store in string.
|
// Generate digits backwards and store in string.
|
||||||
unsigned char buf[10];
|
unsigned char buf[13];
|
||||||
uint8_t i = 0;
|
uint8_t i = 0;
|
||||||
uint32_t a = (long)n;
|
uint32_t a = (long)n;
|
||||||
buf[decimal_places] = '.'; // Place decimal point, even if decimal places are zero.
|
buf[decimal_places] = '.'; // Place decimal point, even if decimal places are zero.
|
||||||
while(a > 0) {
|
while(a > 0) {
|
||||||
if (i == decimal_places) { i++; } // Skip decimal point location
|
if (i == decimal_places) { i++; } // Skip decimal point location
|
||||||
buf[i++] = (a % 10) + '0'; // Get digit
|
buf[i++] = (a % 10) + '0'; // Get digit
|
||||||
a /= 10;
|
a /= 10;
|
||||||
}
|
}
|
||||||
while (i < decimal_places) {
|
while (i < decimal_places) {
|
||||||
buf[i++] = '0'; // Fill in zeros to decimal point for (n < 1)
|
buf[i++] = '0'; // Fill in zeros to decimal point for (n < 1)
|
||||||
}
|
}
|
||||||
if (i == decimal_places) { // Fill in leading zero, if needed.
|
if (i == decimal_places) { // Fill in leading zero, if needed.
|
||||||
i++;
|
i++;
|
||||||
buf[i++] = '0';
|
buf[i++] = '0';
|
||||||
}
|
}
|
||||||
|
|
||||||
// Print the generated string.
|
// Print the generated string.
|
||||||
for (; i > 0; i--)
|
for (; i > 0; i--)
|
||||||
serial_write(buf[i-1]);
|
serial_write(buf[i-1]);
|
||||||
@ -172,16 +173,15 @@ void printFloat(float n, uint8_t decimal_places)
|
|||||||
// in the config.h.
|
// in the config.h.
|
||||||
// - CoordValue: Handles all position or coordinate values in inches or mm reporting.
|
// - CoordValue: Handles all position or coordinate values in inches or mm reporting.
|
||||||
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
|
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
|
||||||
// - SettingValue: Handles all floating point settings values (always in mm.)
|
void printFloat_CoordValue(float n) {
|
||||||
void printFloat_CoordValue(float n) {
|
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
|
||||||
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
|
|
||||||
printFloat(n*INCH_PER_MM,N_DECIMAL_COORDVALUE_INCH);
|
printFloat(n*INCH_PER_MM,N_DECIMAL_COORDVALUE_INCH);
|
||||||
} else {
|
} else {
|
||||||
printFloat(n,N_DECIMAL_COORDVALUE_MM);
|
printFloat(n,N_DECIMAL_COORDVALUE_MM);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void printFloat_RateValue(float n) {
|
void printFloat_RateValue(float n) {
|
||||||
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
|
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
|
||||||
printFloat(n*INCH_PER_MM,N_DECIMAL_RATEVALUE_INCH);
|
printFloat(n*INCH_PER_MM,N_DECIMAL_RATEVALUE_INCH);
|
||||||
} else {
|
} else {
|
||||||
@ -189,17 +189,13 @@ void printFloat_RateValue(float n) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void printFloat_SettingValue(float n) { printFloat(n,N_DECIMAL_SETTINGVALUE); }
|
// Debug tool to print free memory in bytes at the called point.
|
||||||
|
|
||||||
void printFloat_RPMValue(float n) { printFloat(n,N_DECIMAL_RPMVALUE); }
|
|
||||||
|
|
||||||
// Debug tool to print free memory in bytes at the called point.
|
|
||||||
// NOTE: Keep commented unless using. Part of this function always gets compiled in.
|
// NOTE: Keep commented unless using. Part of this function always gets compiled in.
|
||||||
// void printFreeMemory()
|
// void printFreeMemory()
|
||||||
// {
|
// {
|
||||||
// extern int __heap_start, *__brkval;
|
// extern int __heap_start, *__brkval;
|
||||||
// uint16_t free; // Up to 64k values.
|
// uint16_t free; // Up to 64k values.
|
||||||
// free = (int) &free - (__brkval == 0 ? (int) &__heap_start : (int) __brkval);
|
// free = (int) &free - (__brkval == 0 ? (int) &__heap_start : (int) __brkval);
|
||||||
// printInteger((int32_t)free);
|
// printInteger((int32_t)free);
|
||||||
// printString(" ");
|
// printString(" ");
|
||||||
// }
|
// }
|
||||||
|
19
grbl/print.h
19
grbl/print.h
@ -2,7 +2,7 @@
|
|||||||
print.h - Functions for formatting output strings
|
print.h - Functions for formatting output strings
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -31,28 +31,21 @@ void printInteger(long n);
|
|||||||
|
|
||||||
void print_uint32_base10(uint32_t n);
|
void print_uint32_base10(uint32_t n);
|
||||||
|
|
||||||
// Prints uint8 variable with base and number of desired digits.
|
|
||||||
void print_unsigned_int8(uint8_t n, uint8_t base, uint8_t digits);
|
|
||||||
|
|
||||||
// Prints an uint8 variable in base 2.
|
|
||||||
void print_uint8_base2(uint8_t n);
|
|
||||||
|
|
||||||
// Prints an uint8 variable in base 10.
|
// Prints an uint8 variable in base 10.
|
||||||
void print_uint8_base10(uint8_t n);
|
void print_uint8_base10(uint8_t n);
|
||||||
|
|
||||||
|
// Prints an uint8 variable in base 2 with desired number of desired digits.
|
||||||
|
void print_uint8_base2_ndigit(uint8_t n, uint8_t digits);
|
||||||
|
|
||||||
void printFloat(float n, uint8_t decimal_places);
|
void printFloat(float n, uint8_t decimal_places);
|
||||||
|
|
||||||
// Floating value printing handlers for special variables types used in Grbl.
|
// Floating value printing handlers for special variables types used in Grbl.
|
||||||
// - CoordValue: Handles all position or coordinate values in inches or mm reporting.
|
// - CoordValue: Handles all position or coordinate values in inches or mm reporting.
|
||||||
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
|
// - RateValue: Handles feed rate and current velocity in inches or mm reporting.
|
||||||
// - SettingValue: Handles all floating point settings values (always in mm.)
|
|
||||||
// - RPMValue: Handles spindle RPM values in settings and reports.
|
|
||||||
void printFloat_CoordValue(float n);
|
void printFloat_CoordValue(float n);
|
||||||
void printFloat_RateValue(float n);
|
void printFloat_RateValue(float n);
|
||||||
void printFloat_SettingValue(float n);
|
|
||||||
void printFloat_RPMValue(float n);
|
|
||||||
|
|
||||||
// Debug tool to print free memory in bytes at the called point. Not used otherwise.
|
// Debug tool to print free memory in bytes at the called point. Not used otherwise.
|
||||||
void printFreeMemory();
|
void printFreeMemory();
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
24
grbl/probe.c
24
grbl/probe.c
@ -2,7 +2,7 @@
|
|||||||
probe.c - code pertaining to probing methods
|
probe.c - code pertaining to probing methods
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2014-2015 Sungeun K. Jeon
|
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -17,7 +17,7 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
|
|
||||||
|
|
||||||
@ -26,7 +26,7 @@ uint8_t probe_invert_mask;
|
|||||||
|
|
||||||
|
|
||||||
// Probe pin initialization routine.
|
// Probe pin initialization routine.
|
||||||
void probe_init()
|
void probe_init()
|
||||||
{
|
{
|
||||||
PROBE_DDR &= ~(PROBE_MASK); // Configure as input pins
|
PROBE_DDR &= ~(PROBE_MASK); // Configure as input pins
|
||||||
#ifdef DISABLE_PROBE_PIN_PULL_UP
|
#ifdef DISABLE_PROBE_PIN_PULL_UP
|
||||||
@ -34,13 +34,13 @@ void probe_init()
|
|||||||
#else
|
#else
|
||||||
PROBE_PORT |= PROBE_MASK; // Enable internal pull-up resistors. Normal high operation.
|
PROBE_PORT |= PROBE_MASK; // Enable internal pull-up resistors. Normal high operation.
|
||||||
#endif
|
#endif
|
||||||
probe_configure_invert_mask(false); // Initialize invert mask. Re-updated during use.
|
probe_configure_invert_mask(false); // Initialize invert mask.
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
|
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
|
||||||
// appropriately set the pin logic according to setting for normal-high/normal-low operation
|
// appropriately set the pin logic according to setting for normal-high/normal-low operation
|
||||||
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
||||||
void probe_configure_invert_mask(uint8_t is_probe_away)
|
void probe_configure_invert_mask(uint8_t is_probe_away)
|
||||||
{
|
{
|
||||||
probe_invert_mask = 0; // Initialize as zero.
|
probe_invert_mask = 0; // Initialize as zero.
|
||||||
@ -58,11 +58,9 @@ uint8_t probe_get_state() { return((PROBE_PIN & PROBE_MASK) ^ probe_invert_mask)
|
|||||||
// NOTE: This function must be extremely efficient as to not bog down the stepper ISR.
|
// NOTE: This function must be extremely efficient as to not bog down the stepper ISR.
|
||||||
void probe_state_monitor()
|
void probe_state_monitor()
|
||||||
{
|
{
|
||||||
if (sys_probe_state == PROBE_ACTIVE) {
|
if (probe_get_state()) {
|
||||||
if (probe_get_state()) {
|
sys_probe_state = PROBE_OFF;
|
||||||
sys_probe_state = PROBE_OFF;
|
memcpy(sys_probe_position, sys_position, sizeof(sys_position));
|
||||||
memcpy(sys.probe_position, sys.position, sizeof(sys.position));
|
bit_true(sys_rt_exec_state, EXEC_MOTION_CANCEL);
|
||||||
bit_true(sys_rt_exec_state, EXEC_MOTION_CANCEL);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
16
grbl/probe.h
16
grbl/probe.h
@ -2,7 +2,7 @@
|
|||||||
probe.h - code pertaining to probing methods
|
probe.h - code pertaining to probing methods
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2014-2015 Sungeun K. Jeon
|
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -17,20 +17,20 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef probe_h
|
|
||||||
#define probe_h
|
|
||||||
|
|
||||||
// Values that define the probing state machine.
|
#ifndef probe_h
|
||||||
|
#define probe_h
|
||||||
|
|
||||||
|
// Values that define the probing state machine.
|
||||||
#define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.)
|
#define PROBE_OFF 0 // Probing disabled or not in use. (Must be zero.)
|
||||||
#define PROBE_ACTIVE 1 // Actively watching the input pin.
|
#define PROBE_ACTIVE 1 // Actively watching the input pin.
|
||||||
|
|
||||||
// Probe pin initialization routine.
|
// Probe pin initialization routine.
|
||||||
void probe_init();
|
void probe_init();
|
||||||
|
|
||||||
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
|
// Called by probe_init() and the mc_probe() routines. Sets up the probe pin invert mask to
|
||||||
// appropriately set the pin logic according to setting for normal-high/normal-low operation
|
// appropriately set the pin logic according to setting for normal-high/normal-low operation
|
||||||
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
// and the probing cycle modes for toward-workpiece/away-from-workpiece.
|
||||||
void probe_configure_invert_mask(uint8_t is_probe_away);
|
void probe_configure_invert_mask(uint8_t is_probe_away);
|
||||||
|
|
||||||
// Returns probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
|
// Returns probe pin state. Triggered = true. Called by gcode parser and probe state monitor.
|
||||||
|
733
grbl/protocol.c
733
grbl/protocol.c
@ -1,8 +1,8 @@
|
|||||||
/*
|
/*
|
||||||
protocol.c - controls Grbl execution protocol and procedures
|
protocol.c - controls Grbl execution protocol and procedures
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -32,35 +32,42 @@ static char line[LINE_BUFFER_SIZE]; // Line to be executed. Zero-terminated.
|
|||||||
static void protocol_exec_rt_suspend();
|
static void protocol_exec_rt_suspend();
|
||||||
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
GRBL PRIMARY LOOP:
|
GRBL PRIMARY LOOP:
|
||||||
*/
|
*/
|
||||||
void protocol_main_loop()
|
void protocol_main_loop()
|
||||||
{
|
{
|
||||||
// ------------------------------------------------------------
|
// Perform some machine checks to make sure everything is good to go.
|
||||||
// Complete initialization procedures upon a power-up or reset.
|
#ifdef CHECK_LIMITS_AT_INIT
|
||||||
// ------------------------------------------------------------
|
if (bit_istrue(settings.flags, BITFLAG_HARD_LIMIT_ENABLE)) {
|
||||||
|
if (limits_get_state()) {
|
||||||
// Print welcome message
|
sys.state = STATE_ALARM; // Ensure alarm state is active.
|
||||||
report_init_message();
|
report_feedback_message(MESSAGE_CHECK_LIMITS);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
// Check for and report alarm state after a reset, error, or an initial power up.
|
// Check for and report alarm state after a reset, error, or an initial power up.
|
||||||
if (sys.state == STATE_ALARM) {
|
// NOTE: Sleep mode disables the stepper drivers and position can't be guaranteed.
|
||||||
report_feedback_message(MESSAGE_ALARM_LOCK);
|
// Re-initialize the sleep state as an ALARM mode to ensure user homes or acknowledges.
|
||||||
|
if (sys.state & (STATE_ALARM | STATE_SLEEP)) {
|
||||||
|
report_feedback_message(MESSAGE_ALARM_LOCK);
|
||||||
|
sys.state = STATE_ALARM; // Ensure alarm state is set.
|
||||||
} else {
|
} else {
|
||||||
// All systems go! But first check for safety door.
|
// Check if the safety door is open.
|
||||||
sys.state = STATE_IDLE;
|
sys.state = STATE_IDLE;
|
||||||
if (system_check_safety_door_ajar()) {
|
if (system_check_safety_door_ajar()) {
|
||||||
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
||||||
protocol_execute_realtime(); // Enter safety door mode. Should return as IDLE state.
|
protocol_execute_realtime(); // Enter safety door mode. Should return as IDLE state.
|
||||||
}
|
}
|
||||||
|
// All systems go!
|
||||||
system_execute_startup(line); // Execute startup script.
|
system_execute_startup(line); // Execute startup script.
|
||||||
}
|
}
|
||||||
|
|
||||||
// ---------------------------------------------------------------------------------
|
// ---------------------------------------------------------------------------------
|
||||||
// Primary loop! Upon a system abort, this exits back to main() to reset the system.
|
// Primary loop! Upon a system abort, this exits back to main() to reset the system.
|
||||||
// ---------------------------------------------------------------------------------
|
// This is also where Grbl idles while waiting for something to do.
|
||||||
|
// ---------------------------------------------------------------------------------
|
||||||
|
|
||||||
uint8_t line_flags = 0;
|
uint8_t line_flags = 0;
|
||||||
uint8_t char_counter = 0;
|
uint8_t char_counter = 0;
|
||||||
uint8_t c;
|
uint8_t c;
|
||||||
@ -68,19 +75,11 @@ void protocol_main_loop()
|
|||||||
|
|
||||||
// Process one line of incoming serial data, as the data becomes available. Performs an
|
// Process one line of incoming serial data, as the data becomes available. Performs an
|
||||||
// initial filtering by removing spaces and comments and capitalizing all letters.
|
// initial filtering by removing spaces and comments and capitalizing all letters.
|
||||||
|
|
||||||
// NOTE: While comment, spaces, and block delete(if supported) handling should technically
|
|
||||||
// be done in the g-code parser, doing it here helps compress the incoming data into Grbl's
|
|
||||||
// line buffer, which is limited in size. The g-code standard actually states a line can't
|
|
||||||
// exceed 256 characters, but the Arduino Uno does not have the memory space for this.
|
|
||||||
// With a better processor, it would be very easy to pull this initial parsing out as a
|
|
||||||
// seperate task to be shared by the g-code parser and Grbl's system commands.
|
|
||||||
|
|
||||||
while((c = serial_read()) != SERIAL_NO_DATA) {
|
while((c = serial_read()) != SERIAL_NO_DATA) {
|
||||||
if ((c == '\n') || (c == '\r')) { // End of line reached
|
if ((c == '\n') || (c == '\r')) { // End of line reached
|
||||||
|
|
||||||
protocol_execute_realtime(); // Runtime command check point.
|
protocol_execute_realtime(); // Runtime command check point.
|
||||||
if (sys.abort) { return; } // Bail to calling function upon system abort
|
if (sys.abort) { return; } // Bail to calling function upon system abort
|
||||||
|
|
||||||
line[char_counter] = 0; // Set string termination character.
|
line[char_counter] = 0; // Set string termination character.
|
||||||
#ifdef REPORT_ECHO_LINE_RECEIVED
|
#ifdef REPORT_ECHO_LINE_RECEIVED
|
||||||
@ -90,27 +89,27 @@ void protocol_main_loop()
|
|||||||
// Direct and execute one line of formatted input, and report status of execution.
|
// Direct and execute one line of formatted input, and report status of execution.
|
||||||
if (line_flags & LINE_FLAG_OVERFLOW) {
|
if (line_flags & LINE_FLAG_OVERFLOW) {
|
||||||
// Report line overflow error.
|
// Report line overflow error.
|
||||||
report_status_message(STATUS_OVERFLOW);
|
report_status_message(STATUS_OVERFLOW);
|
||||||
} else if (line[0] == 0) {
|
} else if (line[0] == 0) {
|
||||||
// Empty or comment line. For syncing purposes.
|
// Empty or comment line. For syncing purposes.
|
||||||
report_status_message(STATUS_OK);
|
report_status_message(STATUS_OK);
|
||||||
} else if (line[0] == '$') {
|
} else if (line[0] == '$') {
|
||||||
// Grbl '$' system command
|
// Grbl '$' system command
|
||||||
report_status_message(system_execute_line(line));
|
report_status_message(system_execute_line(line));
|
||||||
} else if (sys.state == STATE_ALARM) {
|
} else if (sys.state & (STATE_ALARM | STATE_JOG)) {
|
||||||
// Everything else is gcode. Block if in alarm mode.
|
// Everything else is gcode. Block if in alarm or jog mode.
|
||||||
report_status_message(STATUS_ALARM_LOCK);
|
report_status_message(STATUS_SYSTEM_GC_LOCK);
|
||||||
} else {
|
} else {
|
||||||
// Parse and execute g-code block.
|
// Parse and execute g-code block.
|
||||||
report_status_message(gc_execute_line(line));
|
report_status_message(gc_execute_line(line));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Reset tracking data for next line.
|
// Reset tracking data for next line.
|
||||||
line_flags = 0;
|
line_flags = 0;
|
||||||
char_counter = 0;
|
char_counter = 0;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
if (line_flags) {
|
if (line_flags) {
|
||||||
// Throw away all (except EOL) comment characters and overflow characters.
|
// Throw away all (except EOL) comment characters and overflow characters.
|
||||||
if (c == ')') {
|
if (c == ')') {
|
||||||
@ -118,9 +117,9 @@ void protocol_main_loop()
|
|||||||
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); }
|
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); }
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
if (c <= ' ') {
|
if (c <= ' ') {
|
||||||
// Throw away whitepace and control characters
|
// Throw away whitepace and control characters
|
||||||
} else if (c == '/') {
|
} else if (c == '/') {
|
||||||
// Block delete NOT SUPPORTED. Ignore character.
|
// Block delete NOT SUPPORTED. Ignore character.
|
||||||
// NOTE: If supported, would simply need to check the system if block delete is enabled.
|
// NOTE: If supported, would simply need to check the system if block delete is enabled.
|
||||||
} else if (c == '(') {
|
} else if (c == '(') {
|
||||||
@ -132,11 +131,11 @@ void protocol_main_loop()
|
|||||||
} else if (c == ';') {
|
} else if (c == ';') {
|
||||||
// NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST.
|
// NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST.
|
||||||
line_flags |= LINE_FLAG_COMMENT_SEMICOLON;
|
line_flags |= LINE_FLAG_COMMENT_SEMICOLON;
|
||||||
// TODO: Install '%' feature
|
// TODO: Install '%' feature
|
||||||
// } else if (c == '%') {
|
// } else if (c == '%') {
|
||||||
// Program start-end percent sign NOT SUPPORTED.
|
// Program start-end percent sign NOT SUPPORTED.
|
||||||
// NOTE: This maybe installed to tell Grbl when a program is running vs manual input,
|
// NOTE: This maybe installed to tell Grbl when a program is running vs manual input,
|
||||||
// where, during a program, the system auto-cycle start will continue to execute
|
// where, during a program, the system auto-cycle start will continue to execute
|
||||||
// everything until the next '%' sign. This will help fix resuming issues with certain
|
// everything until the next '%' sign. This will help fix resuming issues with certain
|
||||||
// functions that empty the planner buffer to execute its task on-time.
|
// functions that empty the planner buffer to execute its task on-time.
|
||||||
} else if (char_counter >= (LINE_BUFFER_SIZE-1)) {
|
} else if (char_counter >= (LINE_BUFFER_SIZE-1)) {
|
||||||
@ -148,20 +147,19 @@ void protocol_main_loop()
|
|||||||
line[char_counter++] = c;
|
line[char_counter++] = c;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// If there are no more characters in the serial read buffer to be processed and executed,
|
// If there are no more characters in the serial read buffer to be processed and executed,
|
||||||
// this indicates that g-code streaming has either filled the planner buffer or has
|
// this indicates that g-code streaming has either filled the planner buffer or has
|
||||||
// completed. In either case, auto-cycle start, if enabled, any queued moves.
|
// completed. In either case, auto-cycle start, if enabled, any queued moves.
|
||||||
protocol_auto_cycle_start();
|
protocol_auto_cycle_start();
|
||||||
|
|
||||||
protocol_execute_realtime(); // Runtime command check point.
|
protocol_execute_realtime(); // Runtime command check point.
|
||||||
if (sys.abort) { return; } // Bail to main() program loop to reset system.
|
if (sys.abort) { return; } // Bail to main() program loop to reset system.
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
return; /* Never reached */
|
return; /* Never reached */
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -179,28 +177,28 @@ void protocol_buffer_synchronize()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Auto-cycle start has two purposes: 1. Resumes a plan_synchronize() call from a function that
|
// Auto-cycle start triggers when there is a motion ready to execute and if the main program is not
|
||||||
// requires the planner buffer to empty (spindle enable, dwell, etc.) 2. As a user setting that
|
// actively parsing commands.
|
||||||
// automatically begins the cycle when a user enters a valid motion command manually. This is
|
// NOTE: This function is called from the main loop, buffer sync, and mc_line() only and executes
|
||||||
// intended as a beginners feature to help new users to understand g-code. It can be disabled
|
// when one of these conditions exist respectively: There are no more blocks sent (i.e. streaming
|
||||||
// as a beginner tool, but (1.) still operates. If disabled, the operation of cycle start is
|
// is finished, single commands), a command that needs to wait for the motions in the buffer to
|
||||||
// manually issuing a cycle start command whenever the user is ready and there is a valid motion
|
|
||||||
// command in the planner queue.
|
|
||||||
// NOTE: This function is called from the main loop, buffer sync, and mc_line() only and executes
|
|
||||||
// when one of these conditions exist respectively: There are no more blocks sent (i.e. streaming
|
|
||||||
// is finished, single commands), a command that needs to wait for the motions in the buffer to
|
|
||||||
// execute calls a buffer sync, or the planner buffer is full and ready to go.
|
// execute calls a buffer sync, or the planner buffer is full and ready to go.
|
||||||
void protocol_auto_cycle_start() { system_set_exec_state_flag(EXEC_CYCLE_START); }
|
void protocol_auto_cycle_start()
|
||||||
|
{
|
||||||
|
if (plan_get_current_block() != NULL) { // Check if there are any blocks in the buffer.
|
||||||
|
system_set_exec_state_flag(EXEC_CYCLE_START); // If so, execute them!
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// This function is the general interface to Grbl's real-time command execution system. It is called
|
// This function is the general interface to Grbl's real-time command execution system. It is called
|
||||||
// from various check points in the main program, primarily where there may be a while loop waiting
|
// from various check points in the main program, primarily where there may be a while loop waiting
|
||||||
// for a buffer to clear space or any point where the execution time from the last check point may
|
// for a buffer to clear space or any point where the execution time from the last check point may
|
||||||
// be more than a fraction of a second. This is a way to execute realtime commands asynchronously
|
// be more than a fraction of a second. This is a way to execute realtime commands asynchronously
|
||||||
// (aka multitasking) with grbl's g-code parsing and planning functions. This function also serves
|
// (aka multitasking) with grbl's g-code parsing and planning functions. This function also serves
|
||||||
// as an interface for the interrupts to set the system realtime flags, where only the main program
|
// as an interface for the interrupts to set the system realtime flags, where only the main program
|
||||||
// handles them, removing the need to define more computationally-expensive volatile variables. This
|
// handles them, removing the need to define more computationally-expensive volatile variables. This
|
||||||
// also provides a controlled way to execute certain tasks without having two or more instances of
|
// also provides a controlled way to execute certain tasks without having two or more instances of
|
||||||
// the same task, such as the planner recalculating the buffer upon a feedhold or overrides.
|
// the same task, such as the planner recalculating the buffer upon a feedhold or overrides.
|
||||||
// NOTE: The sys_rt_exec_state variable flags are set by any process, step or serial interrupts, pinouts,
|
// NOTE: The sys_rt_exec_state variable flags are set by any process, step or serial interrupts, pinouts,
|
||||||
// limit switches, or the main program.
|
// limit switches, or the main program.
|
||||||
@ -211,8 +209,8 @@ void protocol_execute_realtime()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Executes run-time commands, when required. This function primarily operates as Grbl's state
|
// Executes run-time commands, when required. This function primarily operates as Grbl's state
|
||||||
// machine and controls the various real-time features Grbl has to offer.
|
// machine and controls the various real-time features Grbl has to offer.
|
||||||
// NOTE: Do not alter this unless you know exactly what you are doing!
|
// NOTE: Do not alter this unless you know exactly what you are doing!
|
||||||
void protocol_exec_rt_system()
|
void protocol_exec_rt_system()
|
||||||
{
|
{
|
||||||
@ -223,149 +221,135 @@ void protocol_exec_rt_system()
|
|||||||
// the source of the error to the user. If critical, Grbl disables by entering an infinite
|
// the source of the error to the user. If critical, Grbl disables by entering an infinite
|
||||||
// loop until system reset/abort.
|
// loop until system reset/abort.
|
||||||
sys.state = STATE_ALARM; // Set system alarm state
|
sys.state = STATE_ALARM; // Set system alarm state
|
||||||
if (rt_exec & EXEC_ALARM_HARD_LIMIT) {
|
report_alarm_message(rt_exec);
|
||||||
report_alarm_message(ALARM_HARD_LIMIT_ERROR);
|
|
||||||
} else if (rt_exec & EXEC_ALARM_SOFT_LIMIT) {
|
|
||||||
report_alarm_message(ALARM_SOFT_LIMIT_ERROR);
|
|
||||||
} else if (rt_exec & EXEC_ALARM_ABORT_CYCLE) {
|
|
||||||
report_alarm_message(ALARM_ABORT_CYCLE);
|
|
||||||
} else if (rt_exec & EXEC_ALARM_PROBE_FAIL) {
|
|
||||||
report_alarm_message(ALARM_PROBE_FAIL);
|
|
||||||
} else if (rt_exec & EXEC_ALARM_HOMING_FAIL) {
|
|
||||||
report_alarm_message(ALARM_HOMING_FAIL);
|
|
||||||
}
|
|
||||||
// Halt everything upon a critical event flag. Currently hard and soft limits flag this.
|
// Halt everything upon a critical event flag. Currently hard and soft limits flag this.
|
||||||
if (rt_exec & EXEC_CRITICAL_EVENT) {
|
if ((rt_exec == EXEC_ALARM_HARD_LIMIT) || (rt_exec == EXEC_ALARM_SOFT_LIMIT)) {
|
||||||
report_feedback_message(MESSAGE_CRITICAL_EVENT);
|
report_feedback_message(MESSAGE_CRITICAL_EVENT);
|
||||||
system_clear_exec_state_flag(EXEC_RESET); // Disable any existing reset
|
system_clear_exec_state_flag(EXEC_RESET); // Disable any existing reset
|
||||||
do {
|
do {
|
||||||
// Block everything, except reset and status reports, until user issues reset or power
|
// Block everything, except reset and status reports, until user issues reset or power
|
||||||
// cycles. Hard limits typically occur while unattended or not paying attention. Gives
|
// cycles. Hard limits typically occur while unattended or not paying attention. Gives
|
||||||
// the user and a GUI time to do what is needed before resetting, like killing the
|
// the user and a GUI time to do what is needed before resetting, like killing the
|
||||||
// incoming stream. The same could be said about soft limits. While the position is not
|
// incoming stream. The same could be said about soft limits. While the position is not
|
||||||
// lost, streaming could cause a serious crash if it continues afterwards.
|
// lost, continued streaming could cause a serious crash if by chance it gets executed.
|
||||||
|
|
||||||
// TODO: Allow status reports during a critical alarm. Still need to think about implications of this.
|
|
||||||
// if (sys_rt_exec_state & EXEC_STATUS_REPORT) {
|
|
||||||
// report_realtime_status();
|
|
||||||
// system_clear_exec_state_flag(EXEC_STATUS_REPORT);
|
|
||||||
// }
|
|
||||||
|
|
||||||
} while (bit_isfalse(sys_rt_exec_state,EXEC_RESET));
|
} while (bit_isfalse(sys_rt_exec_state,EXEC_RESET));
|
||||||
}
|
}
|
||||||
system_clear_exec_alarm_flag(0xFF); // Clear all alarm flags
|
system_clear_exec_alarm_flag(0xFF); // Clear all alarm flags
|
||||||
}
|
}
|
||||||
|
|
||||||
rt_exec = sys_rt_exec_state; // Copy volatile sys_rt_exec_state.
|
rt_exec = sys_rt_exec_state; // Copy volatile sys_rt_exec_state.
|
||||||
if (rt_exec) {
|
if (rt_exec) {
|
||||||
|
|
||||||
// Execute system abort.
|
// Execute system abort.
|
||||||
if (rt_exec & EXEC_RESET) {
|
if (rt_exec & EXEC_RESET) {
|
||||||
sys.abort = true; // Only place this is set true.
|
sys.abort = true; // Only place this is set true.
|
||||||
return; // Nothing else to do but exit.
|
return; // Nothing else to do but exit.
|
||||||
}
|
}
|
||||||
|
|
||||||
// Execute and serial print status
|
// Execute and serial print status
|
||||||
if (rt_exec & EXEC_STATUS_REPORT) {
|
if (rt_exec & EXEC_STATUS_REPORT) {
|
||||||
report_realtime_status();
|
report_realtime_status();
|
||||||
system_clear_exec_state_flag(EXEC_STATUS_REPORT);
|
system_clear_exec_state_flag(EXEC_STATUS_REPORT);
|
||||||
}
|
}
|
||||||
|
|
||||||
// NOTE: The math involved to calculate the hold should be low enough for most, if not all,
|
|
||||||
// operational scenarios. Once hold is initiated, the system enters a suspend state to block
|
|
||||||
// all main program processes until either reset or resumed.
|
|
||||||
if (rt_exec & (EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR)) {
|
|
||||||
|
|
||||||
// TODO: CHECK MODE? How to handle this? Likely nothing, since it only works when IDLE and then resets Grbl.
|
|
||||||
|
|
||||||
// State check for allowable states for hold methods.
|
|
||||||
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_MOTION_CANCEL | STATE_HOLD | STATE_SAFETY_DOOR))) {
|
|
||||||
|
|
||||||
// If in CYCLE state, all hold states immediately initiate a motion HOLD.
|
// NOTE: Once hold is initiated, the system immediately enters a suspend state to block all
|
||||||
if (sys.state == STATE_CYCLE) {
|
// main program processes until either reset or resumed. This ensures a hold completes safely.
|
||||||
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
|
if (rt_exec & (EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR | EXEC_SLEEP)) {
|
||||||
sys.step_control = STEP_CONTROL_EXECUTE_HOLD; // Initiate suspend state with active flag.
|
|
||||||
|
// State check for allowable states for hold methods.
|
||||||
|
if (!(sys.state & (STATE_ALARM | STATE_CHECK_MODE))) {
|
||||||
|
|
||||||
|
// If in CYCLE or JOG states, immediately initiate a motion HOLD.
|
||||||
|
if (sys.state & (STATE_CYCLE | STATE_JOG)) {
|
||||||
|
if (!(sys.suspend & (SUSPEND_MOTION_CANCEL | SUSPEND_JOG_CANCEL))) { // Block, if already holding.
|
||||||
|
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
|
||||||
|
sys.step_control = STEP_CONTROL_EXECUTE_HOLD; // Initiate suspend state with active flag.
|
||||||
|
if (sys.state == STATE_JOG) { // Jog cancelled upon any hold event, except for sleeping.
|
||||||
|
if (!(rt_exec & EXEC_SLEEP)) { sys.suspend |= SUSPEND_JOG_CANCEL; }
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
// If IDLE, Grbl is not in motion. Simply indicate suspend state and hold is complete.
|
// If IDLE, Grbl is not in motion. Simply indicate suspend state and hold is complete.
|
||||||
if (sys.state == STATE_IDLE) {
|
if (sys.state == STATE_IDLE) { sys.suspend = SUSPEND_HOLD_COMPLETE; }
|
||||||
sys.suspend = SUSPEND_HOLD_COMPLETE;
|
|
||||||
sys.step_control = STEP_CONTROL_END_MOTION;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Execute and flag a motion cancel with deceleration and return to idle. Used primarily by probing cycle
|
// Execute and flag a motion cancel with deceleration and return to idle. Used primarily by probing cycle
|
||||||
// to halt and cancel the remainder of the motion.
|
// to halt and cancel the remainder of the motion.
|
||||||
if (rt_exec & EXEC_MOTION_CANCEL) {
|
if (rt_exec & EXEC_MOTION_CANCEL) {
|
||||||
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
|
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
|
||||||
// to hold the CYCLE. If so, only flag that motion cancel is complete.
|
// to hold the CYCLE. Motion cancel is valid for a single planner block motion only, while jog cancel
|
||||||
if (sys.state == STATE_CYCLE) { sys.state = STATE_MOTION_CANCEL; }
|
// will handle and clear multiple planner block motions.
|
||||||
// NOTE: Ensures the motion cancel is handled correctly if it is active during a HOLD or DOOR state.
|
if (!(sys.state & STATE_JOG)) { sys.suspend |= SUSPEND_MOTION_CANCEL; } // NOTE: State is STATE_CYCLE.
|
||||||
sys.suspend |= SUSPEND_MOTION_CANCEL; // Indicate motion cancel when resuming.
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Execute a feed hold with deceleration, if required. Then, suspend system.
|
// Execute a feed hold with deceleration, if required. Then, suspend system.
|
||||||
if (rt_exec & EXEC_FEED_HOLD) {
|
if (rt_exec & EXEC_FEED_HOLD) {
|
||||||
// Block SAFETY_DOOR state from prematurely changing back to HOLD, which should only
|
// Block SAFETY_DOOR, JOG, and SLEEP states from changing to HOLD state.
|
||||||
// occur if the safety door switch closes.
|
if (!(sys.state & (STATE_SAFETY_DOOR | STATE_JOG | STATE_SLEEP))) { sys.state = STATE_HOLD; }
|
||||||
if (sys.state != STATE_SAFETY_DOOR) { sys.state = STATE_HOLD; }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Execute a safety door stop with a feed hold and disable spindle/coolant.
|
// Execute a safety door stop with a feed hold and disable spindle/coolant.
|
||||||
// NOTE: Safety door differs from feed holds by stopping everything no matter state, disables powered
|
// NOTE: Safety door differs from feed holds by stopping everything no matter state, disables powered
|
||||||
// devices (spindle/coolant), and blocks resuming until switch is re-engaged.
|
// devices (spindle/coolant), and blocks resuming until switch is re-engaged.
|
||||||
if (rt_exec & EXEC_SAFETY_DOOR) {
|
if (rt_exec & EXEC_SAFETY_DOOR) {
|
||||||
report_feedback_message(MESSAGE_SAFETY_DOOR_AJAR);
|
report_feedback_message(MESSAGE_SAFETY_DOOR_AJAR);
|
||||||
|
// If jogging, block safety door methods until jog cancel is complete. Just flag that it happened.
|
||||||
// Check if the safety re-opened during a restore parking motion only. Ignore if
|
if (!(sys.suspend & SUSPEND_JOG_CANCEL)) {
|
||||||
// already retracting or parked.
|
// Check if the safety re-opened during a restore parking motion only. Ignore if
|
||||||
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
|
// already retracting, parked or in sleep state.
|
||||||
if (sys.suspend & SUSPEND_INITIATE_RESTORE) { // Actively restoring
|
if (sys.state == STATE_SAFETY_DOOR) {
|
||||||
#ifdef PARKING_ENABLE
|
if (sys.suspend & SUSPEND_INITIATE_RESTORE) { // Actively restoring
|
||||||
// Set hold and reset appropriate control flags to restart parking sequence.
|
#ifdef PARKING_ENABLE
|
||||||
if (sys.step_control & STEP_CONTROL_EXECUTE_PARK) {
|
// Set hold and reset appropriate control flags to restart parking sequence.
|
||||||
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
|
if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) {
|
||||||
sys.step_control = (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_PARK);
|
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
|
||||||
sys.suspend &= ~(SUSPEND_HOLD_COMPLETE);
|
sys.step_control = (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION);
|
||||||
} // else NO_MOTION is active.
|
sys.suspend &= ~(SUSPEND_HOLD_COMPLETE);
|
||||||
#endif
|
} // else NO_MOTION is active.
|
||||||
sys.suspend &= ~(SUSPEND_RETRACT_COMPLETE | SUSPEND_INITIATE_RESTORE | SUSPEND_RESTORE_COMPLETE);
|
#endif
|
||||||
sys.suspend |= SUSPEND_RESTART_RETRACT;
|
sys.suspend &= ~(SUSPEND_RETRACT_COMPLETE | SUSPEND_INITIATE_RESTORE | SUSPEND_RESTORE_COMPLETE);
|
||||||
|
sys.suspend |= SUSPEND_RESTART_RETRACT;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
if (sys.state != STATE_SLEEP) { sys.state = STATE_SAFETY_DOOR; }
|
||||||
}
|
}
|
||||||
|
|
||||||
// NOTE: This flag doesn't change when the door closes, unlike sys.state. Ensures any parking motions
|
// NOTE: This flag doesn't change when the door closes, unlike sys.state. Ensures any parking motions
|
||||||
// are executed if the door switch closes and the state returns to HOLD.
|
// are executed if the door switch closes and the state returns to HOLD.
|
||||||
sys.suspend |= SUSPEND_SAFETY_DOOR_AJAR;
|
sys.suspend |= SUSPEND_SAFETY_DOOR_AJAR;
|
||||||
sys.state = STATE_SAFETY_DOOR;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
system_clear_exec_state_flag((EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR));
|
if (rt_exec & EXEC_SLEEP) {
|
||||||
|
if (sys.state == STATE_ALARM) { sys.suspend |= (SUSPEND_RETRACT_COMPLETE|SUSPEND_HOLD_COMPLETE); }
|
||||||
|
sys.state = STATE_SLEEP;
|
||||||
|
}
|
||||||
|
|
||||||
|
system_clear_exec_state_flag((EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR | EXEC_SLEEP));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Execute a cycle start by starting the stepper interrupt to begin executing the blocks in queue.
|
// Execute a cycle start by starting the stepper interrupt to begin executing the blocks in queue.
|
||||||
if (rt_exec & EXEC_CYCLE_START) {
|
if (rt_exec & EXEC_CYCLE_START) {
|
||||||
// Block if called at same time as the hold commands: feed hold, motion cancel, and safety door.
|
// Block if called at same time as the hold commands: feed hold, motion cancel, and safety door.
|
||||||
// Ensures auto-cycle-start doesn't resume a hold without an explicit user-input.
|
// Ensures auto-cycle-start doesn't resume a hold without an explicit user-input.
|
||||||
if (!(rt_exec & (EXEC_FEED_HOLD | EXEC_MOTION_CANCEL | EXEC_SAFETY_DOOR))) {
|
if (!(rt_exec & (EXEC_FEED_HOLD | EXEC_MOTION_CANCEL | EXEC_SAFETY_DOOR))) {
|
||||||
|
// Resume door state when parking motion has retracted and door has been closed.
|
||||||
|
if ((sys.state == STATE_SAFETY_DOOR) && !(sys.suspend & SUSPEND_SAFETY_DOOR_AJAR)) {
|
||||||
|
if (sys.suspend & SUSPEND_RESTORE_COMPLETE) {
|
||||||
|
sys.state = STATE_IDLE; // Set to IDLE to immediately resume the cycle.
|
||||||
|
} else if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
|
||||||
|
// Flag to re-energize powered components and restore original position, if disabled by SAFETY_DOOR.
|
||||||
|
// NOTE: For a safety door to resume, the switch must be closed, as indicated by HOLD state, and
|
||||||
|
// the retraction execution is complete, which implies the initial feed hold is not active. To
|
||||||
|
// restore normal operation, the restore procedures must be initiated by the following flag. Once,
|
||||||
|
// they are complete, it will call CYCLE_START automatically to resume and exit the suspend.
|
||||||
|
sys.suspend |= SUSPEND_INITIATE_RESTORE;
|
||||||
|
}
|
||||||
|
}
|
||||||
// Cycle start only when IDLE or when a hold is complete and ready to resume.
|
// Cycle start only when IDLE or when a hold is complete and ready to resume.
|
||||||
// NOTE: SAFETY_DOOR is implicitly blocked. It reverts to HOLD when the door is closed.
|
if ((sys.state == STATE_IDLE) || ((sys.state & STATE_HOLD) && (sys.suspend & SUSPEND_HOLD_COMPLETE))) {
|
||||||
if ((sys.state == STATE_IDLE) || ((sys.state & (STATE_HOLD | STATE_MOTION_CANCEL)) && (sys.suspend & SUSPEND_HOLD_COMPLETE))) {
|
if (sys.state == STATE_HOLD && (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK)) {
|
||||||
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
|
sys.toggle_ovr_mask |= TOGGLE_OVR_STOP_RESTORE_CYCLE; // Set to restore in suspend routine and cycle start after.
|
||||||
if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
|
} else {
|
||||||
if bit_isfalse(sys.suspend,SUSPEND_RESTORE_COMPLETE) {
|
|
||||||
// Flag to re-energize powered components and restore original position, if disabled by SAFETY_DOOR.
|
|
||||||
// NOTE: For a safety door to resume, the switch must be closed, as indicated by HOLD state, and
|
|
||||||
// the retraction execution is complete, which implies the initial feed hold is not active. To
|
|
||||||
// restore normal operation, the restore procedures must be initiated by the following flag. Once,
|
|
||||||
// they are complete, it will call CYCLE_START automatically to resume and exit the suspend.
|
|
||||||
sys.suspend |= SUSPEND_INITIATE_RESTORE;
|
|
||||||
} else {
|
|
||||||
bit_false(sys.suspend,SUSPEND_SAFETY_DOOR_AJAR);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (!(sys.suspend & SUSPEND_SAFETY_DOOR_AJAR)) {
|
|
||||||
// Start cycle only if queued motions exist in planner buffer and the motion is not canceled.
|
// Start cycle only if queued motions exist in planner buffer and the motion is not canceled.
|
||||||
sys.step_control = STEP_CONTROL_NORMAL_OP; // Restore step control to normal operation
|
sys.step_control = STEP_CONTROL_NORMAL_OP; // Restore step control to normal operation
|
||||||
if (plan_get_current_block() && bit_isfalse(sys.suspend,SUSPEND_MOTION_CANCEL)) {
|
if (plan_get_current_block() && bit_isfalse(sys.suspend,SUSPEND_MOTION_CANCEL)) {
|
||||||
@ -379,36 +363,145 @@ void protocol_exec_rt_system()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
system_clear_exec_state_flag(EXEC_CYCLE_START);
|
system_clear_exec_state_flag(EXEC_CYCLE_START);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (rt_exec & EXEC_CYCLE_STOP) {
|
if (rt_exec & EXEC_CYCLE_STOP) {
|
||||||
// Reinitializes the cycle plan and stepper system after a feed hold for a resume. Called by
|
// Reinitializes the cycle plan and stepper system after a feed hold for a resume. Called by
|
||||||
// realtime command execution in the main program, ensuring that the planner re-plans safely.
|
// realtime command execution in the main program, ensuring that the planner re-plans safely.
|
||||||
// NOTE: Bresenham algorithm variables are still maintained through both the planner and stepper
|
// NOTE: Bresenham algorithm variables are still maintained through both the planner and stepper
|
||||||
// cycle reinitializations. The stepper path should continue exactly as if nothing has happened.
|
// cycle reinitializations. The stepper path should continue exactly as if nothing has happened.
|
||||||
// NOTE: EXEC_CYCLE_STOP is set by the stepper subsystem when a cycle or feed hold completes.
|
// NOTE: EXEC_CYCLE_STOP is set by the stepper subsystem when a cycle or feed hold completes.
|
||||||
if ((sys.state & (STATE_HOLD | STATE_SAFETY_DOOR)) && !(sys.soft_limit)) {
|
if ((sys.state & (STATE_HOLD|STATE_SAFETY_DOOR|STATE_SLEEP)) && !(sys.soft_limit) && !(sys.suspend & SUSPEND_JOG_CANCEL)) {
|
||||||
// Hold complete. Set to indicate ready to resume. Remain in HOLD or DOOR states until user
|
// Hold complete. Set to indicate ready to resume. Remain in HOLD or DOOR states until user
|
||||||
// has issued a resume command or reset.
|
// has issued a resume command or reset.
|
||||||
plan_cycle_reinitialize();
|
plan_cycle_reinitialize();
|
||||||
if (sys.step_control & STEP_CONTROL_EXECUTE_HOLD) { sys.suspend |= SUSPEND_HOLD_COMPLETE; }
|
if (sys.step_control & STEP_CONTROL_EXECUTE_HOLD) { sys.suspend |= SUSPEND_HOLD_COMPLETE; }
|
||||||
bit_false(sys.step_control,(STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_PARK));
|
bit_false(sys.step_control,(STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION));
|
||||||
} else { // Motion is complete. Includes CYCLE, HOMING, and MOTION_CANCEL states.
|
} else {
|
||||||
sys.suspend = SUSPEND_DISABLE;
|
// Motion complete. Includes CYCLE/JOG/HOMING states and jog cancel/motion cancel/soft limit events.
|
||||||
sys.state = STATE_IDLE;
|
// NOTE: Motion and jog cancel both immediately return to idle after the hold completes.
|
||||||
}
|
if (sys.suspend & SUSPEND_JOG_CANCEL) { // For jog cancel, flush buffers and sync positions.
|
||||||
|
sys.step_control = STEP_CONTROL_NORMAL_OP;
|
||||||
|
plan_reset();
|
||||||
|
st_reset();
|
||||||
|
gc_sync_position();
|
||||||
|
plan_sync_position();
|
||||||
|
}
|
||||||
|
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) { // Only occurs when safety door opens during jog.
|
||||||
|
sys.suspend &= ~(SUSPEND_JOG_CANCEL);
|
||||||
|
sys.suspend |= SUSPEND_HOLD_COMPLETE;
|
||||||
|
sys.state = STATE_SAFETY_DOOR;
|
||||||
|
} else {
|
||||||
|
sys.suspend = SUSPEND_DISABLE;
|
||||||
|
sys.state = STATE_IDLE;
|
||||||
|
}
|
||||||
|
}
|
||||||
system_clear_exec_state_flag(EXEC_CYCLE_STOP);
|
system_clear_exec_state_flag(EXEC_CYCLE_STOP);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Overrides flag byte (sys.override) and execution should be installed here, since they
|
// Execute overrides.
|
||||||
// are realtime and require a direct and controlled interface to the main stepper program.
|
rt_exec = sys_rt_exec_motion_override; // Copy volatile sys_rt_exec_motion_override
|
||||||
|
if (rt_exec) {
|
||||||
|
system_clear_exec_motion_overrides(); // Clear all motion override flags.
|
||||||
|
|
||||||
|
uint8_t new_f_override = sys.f_override;
|
||||||
|
if (rt_exec & EXEC_FEED_OVR_RESET) { new_f_override = DEFAULT_FEED_OVERRIDE; }
|
||||||
|
if (rt_exec & EXEC_FEED_OVR_COARSE_PLUS) { new_f_override += FEED_OVERRIDE_COARSE_INCREMENT; }
|
||||||
|
if (rt_exec & EXEC_FEED_OVR_COARSE_MINUS) { new_f_override -= FEED_OVERRIDE_COARSE_INCREMENT; }
|
||||||
|
if (rt_exec & EXEC_FEED_OVR_FINE_PLUS) { new_f_override += FEED_OVERRIDE_FINE_INCREMENT; }
|
||||||
|
if (rt_exec & EXEC_FEED_OVR_FINE_MINUS) { new_f_override -= FEED_OVERRIDE_FINE_INCREMENT; }
|
||||||
|
new_f_override = min(new_f_override,MAX_FEED_RATE_OVERRIDE);
|
||||||
|
new_f_override = max(new_f_override,MIN_FEED_RATE_OVERRIDE);
|
||||||
|
|
||||||
|
uint8_t new_r_override = sys.r_override;
|
||||||
|
if (rt_exec & EXEC_RAPID_OVR_RESET) { new_r_override = DEFAULT_RAPID_OVERRIDE; }
|
||||||
|
if (rt_exec & EXEC_RAPID_OVR_MEDIUM) { new_r_override = RAPID_OVERRIDE_MEDIUM; }
|
||||||
|
if (rt_exec & EXEC_RAPID_OVR_LOW) { new_r_override = RAPID_OVERRIDE_LOW; }
|
||||||
|
|
||||||
|
if ((new_f_override != sys.f_override) || (new_r_override != sys.r_override)) {
|
||||||
|
sys.f_override = new_f_override;
|
||||||
|
sys.r_override = new_r_override;
|
||||||
|
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to report change immediately
|
||||||
|
plan_update_velocity_profile_parameters();
|
||||||
|
plan_cycle_reinitialize();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
rt_exec = sys_rt_exec_accessory_override;
|
||||||
|
if (rt_exec) {
|
||||||
|
system_clear_exec_accessory_overrides(); // Clear all accessory override flags.
|
||||||
|
|
||||||
|
// NOTE: Unlike motion overrides, spindle overrides do not require a planner reinitialization.
|
||||||
|
uint8_t last_s_override = sys.spindle_speed_ovr;
|
||||||
|
if (rt_exec & EXEC_SPINDLE_OVR_RESET) { last_s_override = DEFAULT_SPINDLE_SPEED_OVERRIDE; }
|
||||||
|
if (rt_exec & EXEC_SPINDLE_OVR_COARSE_PLUS) { last_s_override += SPINDLE_OVERRIDE_COARSE_INCREMENT; }
|
||||||
|
if (rt_exec & EXEC_SPINDLE_OVR_COARSE_MINUS) { last_s_override -= SPINDLE_OVERRIDE_COARSE_INCREMENT; }
|
||||||
|
if (rt_exec & EXEC_SPINDLE_OVR_FINE_PLUS) { last_s_override += SPINDLE_OVERRIDE_FINE_INCREMENT; }
|
||||||
|
if (rt_exec & EXEC_SPINDLE_OVR_FINE_MINUS) { last_s_override -= SPINDLE_OVERRIDE_FINE_INCREMENT; }
|
||||||
|
last_s_override = min(last_s_override,MAX_SPINDLE_SPEED_OVERRIDE);
|
||||||
|
last_s_override = max(last_s_override,MIN_SPINDLE_SPEED_OVERRIDE);
|
||||||
|
|
||||||
|
if (last_s_override != sys.spindle_speed_ovr) {
|
||||||
|
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||||
|
sys.spindle_speed_ovr = last_s_override;
|
||||||
|
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to report change immediately
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t last_toggle_ovr_mask = sys.toggle_ovr_mask;
|
||||||
|
if (rt_exec & EXEC_SPINDLE_OVR_STOP) {
|
||||||
|
// Toggle allowed only while in HOLD state.
|
||||||
|
if (sys.state == STATE_HOLD) {
|
||||||
|
if (!(last_toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK)) { last_toggle_ovr_mask |= TOGGLE_OVR_STOP_INITIATE; }
|
||||||
|
else if (last_toggle_ovr_mask & TOGGLE_OVR_STOP_ENABLED) { last_toggle_ovr_mask |= TOGGLE_OVR_STOP_RESTORE; }
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// NOTE: Since coolant state always performs a planner sync whenever it changes, g-code parser
|
||||||
|
// state can be implicitly determine current run state at the beginning of the planner.
|
||||||
|
if (rt_exec & (EXEC_COOLANT_FLOOD_OVR_TOGGLE | EXEC_COOLANT_MIST_OVR_TOGGLE)) {
|
||||||
|
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOLD))) {
|
||||||
|
uint8_t coolant_state = gc_state.modal.coolant;
|
||||||
|
#ifdef ENABLE_M7
|
||||||
|
if (rt_exec & EXEC_COOLANT_MIST_OVR_TOGGLE) {
|
||||||
|
if (coolant_state & COOLANT_MIST_ENABLE) { bit_false(coolant_state,COOLANT_MIST_ENABLE); }
|
||||||
|
else { coolant_state |= COOLANT_MIST_ENABLE; }
|
||||||
|
last_toggle_ovr_mask |= TOGGLE_OVR_MIST_COOLANT;
|
||||||
|
}
|
||||||
|
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE) {
|
||||||
|
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
|
||||||
|
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
|
||||||
|
last_toggle_ovr_mask |= TOGGLE_OVR_FLOOD_COOLANT;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
|
||||||
|
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
|
||||||
|
last_toggle_ovr_mask |= TOGGLE_OVR_FLOOD_COOLANT;
|
||||||
|
#endif
|
||||||
|
coolant_set_state(coolant_state);
|
||||||
|
gc_state.modal.coolant = coolant_state;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (last_toggle_ovr_mask != sys.toggle_ovr_mask) {
|
||||||
|
sys.toggle_ovr_mask = last_toggle_ovr_mask;
|
||||||
|
sys.report_ovr_counter = REPORT_OVR_REFRESH_BUSY_COUNT; // Set to report change immediately
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef DEBUG
|
||||||
|
if (sys_rt_exec_debug) {
|
||||||
|
report_realtime_debug();
|
||||||
|
sys_rt_exec_debug = 0;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// Reload step segment buffer
|
// Reload step segment buffer
|
||||||
if (sys.state & (STATE_CYCLE | STATE_HOLD | STATE_MOTION_CANCEL | STATE_SAFETY_DOOR | STATE_HOMING)) {
|
if (sys.state & (STATE_CYCLE | STATE_HOLD | STATE_SAFETY_DOOR | STATE_HOMING | STATE_SLEEP| STATE_JOG)) {
|
||||||
st_prep_buffer();
|
st_prep_buffer();
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -418,7 +511,7 @@ void protocol_exec_rt_system()
|
|||||||
// The system will enter this loop, create local variables for suspend tasks, and return to
|
// The system will enter this loop, create local variables for suspend tasks, and return to
|
||||||
// whatever function that invoked the suspend, such that Grbl resumes normal operation.
|
// whatever function that invoked the suspend, such that Grbl resumes normal operation.
|
||||||
// This function is written in a way to promote custom parking motions. Simply use this as a
|
// This function is written in a way to promote custom parking motions. Simply use this as a
|
||||||
// template
|
// template
|
||||||
static void protocol_exec_rt_suspend()
|
static void protocol_exec_rt_suspend()
|
||||||
{
|
{
|
||||||
#ifdef PARKING_ENABLE
|
#ifdef PARKING_ENABLE
|
||||||
@ -426,131 +519,219 @@ static void protocol_exec_rt_suspend()
|
|||||||
float restore_target[N_AXIS];
|
float restore_target[N_AXIS];
|
||||||
float parking_target[N_AXIS];
|
float parking_target[N_AXIS];
|
||||||
float retract_waypoint = PARKING_PULLOUT_INCREMENT;
|
float retract_waypoint = PARKING_PULLOUT_INCREMENT;
|
||||||
|
plan_line_data_t plan_data;
|
||||||
|
plan_line_data_t *pl_data = &plan_data;
|
||||||
|
memset(pl_data,0,sizeof(plan_line_data_t));
|
||||||
|
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION|PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||||
|
#ifdef USE_LINE_NUMBERS
|
||||||
|
pl_data->line_number = PARKING_MOTION_LINE_NUMBER;
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
plan_block_t *block = plan_get_current_block();
|
||||||
|
uint8_t restore_condition;
|
||||||
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
float restore_spindle_speed;
|
||||||
|
if (block == NULL) {
|
||||||
|
restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
|
||||||
|
restore_spindle_speed = gc_state.spindle_speed;
|
||||||
|
} else {
|
||||||
|
restore_condition = block->condition;
|
||||||
|
restore_spindle_speed = block->spindle_speed;
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
float restore_spindle_speed = 0.0; // Without variable spindle, this value is unused.
|
||||||
|
if (block == NULL) { restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant); }
|
||||||
|
else { restore_condition = block->condition; }
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
while (sys.suspend) {
|
while (sys.suspend) {
|
||||||
|
|
||||||
if (sys.abort) { return; }
|
if (sys.abort) { return; }
|
||||||
|
|
||||||
// Safety door manager. Handles de/re-energizing, switch state checks, and parking motions.
|
|
||||||
if ((sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) && (sys.suspend & SUSPEND_HOLD_COMPLETE)) {
|
|
||||||
|
|
||||||
// Handles retraction motions and de-energizing.
|
|
||||||
if (bit_isfalse(sys.suspend,SUSPEND_RETRACT_COMPLETE)) {
|
|
||||||
|
|
||||||
#ifndef PARKING_ENABLE
|
// Block until initial hold is complete and the machine has stopped motion.
|
||||||
|
if (sys.suspend & SUSPEND_HOLD_COMPLETE) {
|
||||||
spindle_stop(); // De-energize
|
|
||||||
coolant_stop(); // De-energize
|
// Parking manager. Handles de/re-energizing, switch state checks, and parking motions for
|
||||||
|
// the safety door and sleep states.
|
||||||
#else
|
if (sys.state & (STATE_SAFETY_DOOR | STATE_SLEEP)) {
|
||||||
|
|
||||||
// Get current position and store restore location and spindle retract waypoint.
|
// Handles retraction motions and de-energizing.
|
||||||
system_convert_array_steps_to_mpos(parking_target,sys.position);
|
if (bit_isfalse(sys.suspend,SUSPEND_RETRACT_COMPLETE)) {
|
||||||
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
|
||||||
memcpy(restore_target,parking_target,sizeof(parking_target));
|
// Ensure any prior spindle stop override is disabled at start of safety door routine.
|
||||||
retract_waypoint += restore_target[PARKING_AXIS];
|
bit_false(sys.toggle_ovr_mask,TOGGLE_OVR_STOP_ACTIVE_MASK);
|
||||||
retract_waypoint = min(retract_waypoint,PARKING_TARGET);
|
|
||||||
}
|
#ifndef PARKING_ENABLE
|
||||||
|
|
||||||
// Execute slow pull-out parking retract motion. Parking requires homing enabled and
|
|
||||||
// the current location not exceeding the parking target location.
|
|
||||||
// NOTE: State is will remain DOOR, until the de-energizing and retract is complete.
|
|
||||||
if ((bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) &&
|
|
||||||
(parking_target[PARKING_AXIS] < PARKING_TARGET)) {
|
|
||||||
|
|
||||||
// Retract spindle by pullout distance. Ensure retraction motion moves away from
|
|
||||||
// the workpiece and waypoint motion doesn't exceed the parking target location.
|
|
||||||
if (parking_target[PARKING_AXIS] < retract_waypoint) {
|
|
||||||
parking_target[PARKING_AXIS] = retract_waypoint;
|
|
||||||
mc_parking_motion(parking_target, PARKING_PULLOUT_RATE);
|
|
||||||
}
|
|
||||||
|
|
||||||
spindle_stop(); // De-energize
|
spindle_stop(); // De-energize
|
||||||
coolant_stop(); // De-energize
|
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||||
|
|
||||||
// Execute fast parking retract motion to parking target location.
|
#else
|
||||||
if (parking_target[PARKING_AXIS] < PARKING_TARGET) {
|
|
||||||
parking_target[PARKING_AXIS] = PARKING_TARGET;
|
// Get current position and store restore location and spindle retract waypoint.
|
||||||
mc_parking_motion(parking_target, PARKING_RATE);
|
system_convert_array_steps_to_mpos(parking_target,sys_position);
|
||||||
|
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
||||||
|
memcpy(restore_target,parking_target,sizeof(parking_target));
|
||||||
|
retract_waypoint += restore_target[PARKING_AXIS];
|
||||||
|
retract_waypoint = min(retract_waypoint,PARKING_TARGET);
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
|
||||||
|
|
||||||
// Parking motion not possible. Just disable the spindle and coolant.
|
|
||||||
spindle_stop(); // De-energize
|
|
||||||
coolant_stop(); // De-energize
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
|
// Execute slow pull-out parking retract motion. Parking requires homing enabled, the
|
||||||
sys.suspend |= SUSPEND_RETRACT_COMPLETE;
|
// current location not exceeding the parking target location, and laser mode disabled.
|
||||||
|
|
||||||
} else {
|
|
||||||
|
|
||||||
// Allows resuming from parking/safety door. Actively checks if safety door is closed and ready to resume.
|
|
||||||
// NOTE: This unlocks the SAFETY_DOOR state to a HOLD state, such that CYCLE_START can activate a resume.
|
|
||||||
if (sys.state == STATE_SAFETY_DOOR) {
|
|
||||||
if (!(system_check_safety_door_ajar())) {
|
|
||||||
sys.state = STATE_HOLD; // Update to HOLD state to indicate door is closed and ready to resume.
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Handles parking restore and safety door resume.
|
|
||||||
if (sys.suspend & SUSPEND_INITIATE_RESTORE) {
|
|
||||||
|
|
||||||
#ifdef PARKING_ENABLE
|
|
||||||
// Execute fast restore motion to the pull-out position. Parking requires homing enabled.
|
|
||||||
// NOTE: State is will remain DOOR, until the de-energizing and retract is complete.
|
// NOTE: State is will remain DOOR, until the de-energizing and retract is complete.
|
||||||
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
|
if ((bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) &&
|
||||||
// Check to ensure the motion doesn't move below pull-out position.
|
(parking_target[PARKING_AXIS] < PARKING_TARGET) &&
|
||||||
if (parking_target[PARKING_AXIS] <= PARKING_TARGET) {
|
bit_isfalse(settings.flags,BITFLAG_LASER_MODE)) {
|
||||||
|
|
||||||
|
// Retract spindle by pullout distance. Ensure retraction motion moves away from
|
||||||
|
// the workpiece and waypoint motion doesn't exceed the parking target location.
|
||||||
|
if (parking_target[PARKING_AXIS] < retract_waypoint) {
|
||||||
parking_target[PARKING_AXIS] = retract_waypoint;
|
parking_target[PARKING_AXIS] = retract_waypoint;
|
||||||
mc_parking_motion(parking_target, PARKING_RATE);
|
pl_data->feed_rate = PARKING_PULLOUT_RATE;
|
||||||
|
mc_parking_motion(parking_target, pl_data);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
spindle_stop(); // De-energize
|
||||||
|
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||||
|
|
||||||
|
// Execute fast parking retract motion to parking target location.
|
||||||
|
if (parking_target[PARKING_AXIS] < PARKING_TARGET) {
|
||||||
|
parking_target[PARKING_AXIS] = PARKING_TARGET;
|
||||||
|
pl_data->feed_rate = PARKING_RATE;
|
||||||
|
mc_parking_motion(parking_target, pl_data);
|
||||||
|
}
|
||||||
|
|
||||||
|
} else {
|
||||||
|
|
||||||
|
// Parking motion not possible. Just disable the spindle and coolant.
|
||||||
|
// NOTE: Laser mode does not start a parking motion to ensure the laser stops immediately.
|
||||||
|
spindle_stop(); // De-energize
|
||||||
|
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Delayed Tasks: Restart spindle and coolant, delay to power-up, then resume cycle.
|
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
|
||||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
sys.suspend |= SUSPEND_RETRACT_COMPLETE;
|
||||||
// Block if safety door re-opened during prior restore actions.
|
|
||||||
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
} else {
|
||||||
spindle_set_state(gc_state.modal.spindle, gc_state.spindle_speed);
|
|
||||||
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SAFETY_DOOR);
|
|
||||||
|
if (sys.state == STATE_SLEEP) {
|
||||||
|
report_feedback_message(MESSAGE_SLEEP_MODE);
|
||||||
|
// Spindle and coolant should already be stopped, but do it again just to be sure.
|
||||||
|
spindle_stop(); // De-energize
|
||||||
|
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||||
|
st_go_idle(); // Disable steppers
|
||||||
|
while (!(sys.abort)) { protocol_exec_rt_system(); } // Do nothing until reset.
|
||||||
|
return; // Abort received. Return to re-initialize.
|
||||||
|
}
|
||||||
|
|
||||||
|
// Allows resuming from parking/safety door. Actively checks if safety door is closed and ready to resume.
|
||||||
|
if (sys.state == STATE_SAFETY_DOOR) {
|
||||||
|
if (!(system_check_safety_door_ajar())) {
|
||||||
|
sys.suspend &= ~(SUSPEND_SAFETY_DOOR_AJAR); // Reset door ajar flag to denote ready to resume.
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (gc_state.modal.coolant != COOLANT_DISABLE) {
|
|
||||||
// Block if safety door re-opened during prior restore actions.
|
// Handles parking restore and safety door resume.
|
||||||
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
if (sys.suspend & SUSPEND_INITIATE_RESTORE) {
|
||||||
coolant_set_state(gc_state.modal.coolant);
|
|
||||||
delay_sec(SAFETY_DOOR_COOLANT_DELAY, DELAY_MODE_SAFETY_DOOR);
|
#ifdef PARKING_ENABLE
|
||||||
}
|
// Execute fast restore motion to the pull-out position. Parking requires homing enabled.
|
||||||
}
|
// NOTE: State is will remain DOOR, until the de-energizing and retract is complete.
|
||||||
|
if ((settings.flags & (BITFLAG_HOMING_ENABLE|BITFLAG_LASER_MODE)) == BITFLAG_HOMING_ENABLE) {
|
||||||
#ifdef PARKING_ENABLE
|
// Check to ensure the motion doesn't move below pull-out position.
|
||||||
// Execute slow plunge motion from pull-out position to resume position.
|
if (parking_target[PARKING_AXIS] <= PARKING_TARGET) {
|
||||||
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
|
parking_target[PARKING_AXIS] = retract_waypoint;
|
||||||
|
pl_data->feed_rate = PARKING_RATE;
|
||||||
|
mc_parking_motion(parking_target, pl_data);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Delayed Tasks: Restart spindle and coolant, delay to power-up, then resume cycle.
|
||||||
|
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||||
// Block if safety door re-opened during prior restore actions.
|
// Block if safety door re-opened during prior restore actions.
|
||||||
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
||||||
// Regardless if the retract parking motion was a valid/safe motion or not, the
|
if (bit_istrue(settings.flags,BITFLAG_LASER_MODE)) {
|
||||||
// restore parking motion should logically be valid, either by returning to the
|
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||||
// original position through valid machine space or by not moving at all.
|
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||||
mc_parking_motion(restore_target, PARKING_PULLOUT_RATE);
|
} else {
|
||||||
}
|
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||||
|
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (gc_state.modal.coolant != COOLANT_DISABLE) {
|
||||||
|
// Block if safety door re-opened during prior restore actions.
|
||||||
|
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
||||||
|
// NOTE: Laser mode will honor this delay. An exhaust system is often controlled by this pin.
|
||||||
|
coolant_set_state((restore_condition & (PL_COND_FLAG_COOLANT_FLOOD | PL_COND_FLAG_COOLANT_FLOOD)));
|
||||||
|
delay_sec(SAFETY_DOOR_COOLANT_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef PARKING_ENABLE
|
||||||
|
// Execute slow plunge motion from pull-out position to resume position.
|
||||||
|
if ((settings.flags & (BITFLAG_HOMING_ENABLE|BITFLAG_LASER_MODE)) == BITFLAG_HOMING_ENABLE) {
|
||||||
|
// Block if safety door re-opened during prior restore actions.
|
||||||
|
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
||||||
|
// Regardless if the retract parking motion was a valid/safe motion or not, the
|
||||||
|
// restore parking motion should logically be valid, either by returning to the
|
||||||
|
// original position through valid machine space or by not moving at all.
|
||||||
|
pl_data->feed_rate = PARKING_PULLOUT_RATE;
|
||||||
|
mc_parking_motion(restore_target, pl_data);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
||||||
|
sys.suspend |= SUSPEND_RESTORE_COMPLETE;
|
||||||
|
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
|
|
||||||
sys.suspend |= SUSPEND_RESTORE_COMPLETE;
|
|
||||||
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
} else {
|
||||||
|
|
||||||
|
// Feed hold manager. Controls spindle stop override states.
|
||||||
|
// NOTE: Hold ensured as completed by condition check at the beginning of suspend routine.
|
||||||
|
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_INITIATE) { // Handles beginning of spindle stop
|
||||||
|
|
||||||
|
bit_false(sys.toggle_ovr_mask,TOGGLE_OVR_STOP_ACTIVE_MASK); // Clear stop override state
|
||||||
|
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||||
|
spindle_stop(); // De-energize
|
||||||
|
sys.toggle_ovr_mask |= TOGGLE_OVR_STOP_ENABLED; // Set stop override state to enabled, if de-energized.
|
||||||
|
}
|
||||||
|
|
||||||
|
} else if (sys.toggle_ovr_mask & (TOGGLE_OVR_STOP_RESTORE | TOGGLE_OVR_STOP_RESTORE_CYCLE)) { // Handles restoring of spindle state
|
||||||
|
|
||||||
|
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||||
|
report_feedback_message(MESSAGE_SPINDLE_RESTORE);
|
||||||
|
if (bit_istrue(settings.flags,BITFLAG_LASER_MODE)) {
|
||||||
|
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||||
|
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||||
|
} else {
|
||||||
|
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||||
|
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_RESTORE_CYCLE) {
|
||||||
|
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
|
||||||
|
}
|
||||||
|
bit_false(sys.toggle_ovr_mask,TOGGLE_OVR_STOP_ACTIVE_MASK); // Clear stop override state
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
protocol_exec_rt_system();
|
protocol_exec_rt_system();
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
protocol.h - controls Grbl execution protocol and procedures
|
protocol.h - controls Grbl execution protocol and procedures
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -26,7 +26,7 @@
|
|||||||
// NOTE: Not a problem except for extreme cases, but the line buffer size can be too small
|
// NOTE: Not a problem except for extreme cases, but the line buffer size can be too small
|
||||||
// and g-code blocks can get truncated. Officially, the g-code standards support up to 256
|
// and g-code blocks can get truncated. Officially, the g-code standards support up to 256
|
||||||
// characters. In future versions, this will be increased, when we know how much extra
|
// characters. In future versions, this will be increased, when we know how much extra
|
||||||
// memory space we can invest into here or we re-write the g-code parser not to have this
|
// memory space we can invest into here or we re-write the g-code parser not to have this
|
||||||
// buffer.
|
// buffer.
|
||||||
#ifndef LINE_BUFFER_SIZE
|
#ifndef LINE_BUFFER_SIZE
|
||||||
#define LINE_BUFFER_SIZE 80
|
#define LINE_BUFFER_SIZE 80
|
||||||
@ -40,15 +40,6 @@ void protocol_main_loop();
|
|||||||
void protocol_execute_realtime();
|
void protocol_execute_realtime();
|
||||||
void protocol_exec_rt_system();
|
void protocol_exec_rt_system();
|
||||||
|
|
||||||
// Notify the stepper subsystem to start executing the g-code program in buffer.
|
|
||||||
// void protocol_cycle_start();
|
|
||||||
|
|
||||||
// Reinitializes the buffer after a feed hold for a resume.
|
|
||||||
// void protocol_cycle_reinitialize();
|
|
||||||
|
|
||||||
// Initiates a feed hold of the running program
|
|
||||||
// void protocol_feed_hold();
|
|
||||||
|
|
||||||
// Executes the auto cycle feature, if enabled.
|
// Executes the auto cycle feature, if enabled.
|
||||||
void protocol_auto_cycle_start();
|
void protocol_auto_cycle_start();
|
||||||
|
|
||||||
|
959
grbl/report.c
959
grbl/report.c
File diff suppressed because it is too large
Load Diff
@ -2,7 +2,7 @@
|
|||||||
report.h - reporting and messaging methods
|
report.h - reporting and messaging methods
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -20,7 +20,7 @@
|
|||||||
#ifndef report_h
|
#ifndef report_h
|
||||||
#define report_h
|
#define report_h
|
||||||
|
|
||||||
// Define Grbl status codes.
|
// Define Grbl status codes. Valid values (0-255)
|
||||||
#define STATUS_OK 0
|
#define STATUS_OK 0
|
||||||
#define STATUS_EXPECTED_COMMAND_LETTER 1
|
#define STATUS_EXPECTED_COMMAND_LETTER 1
|
||||||
#define STATUS_BAD_NUMBER_FORMAT 2
|
#define STATUS_BAD_NUMBER_FORMAT 2
|
||||||
@ -30,11 +30,14 @@
|
|||||||
#define STATUS_SETTING_STEP_PULSE_MIN 6
|
#define STATUS_SETTING_STEP_PULSE_MIN 6
|
||||||
#define STATUS_SETTING_READ_FAIL 7
|
#define STATUS_SETTING_READ_FAIL 7
|
||||||
#define STATUS_IDLE_ERROR 8
|
#define STATUS_IDLE_ERROR 8
|
||||||
#define STATUS_ALARM_LOCK 9
|
#define STATUS_SYSTEM_GC_LOCK 9
|
||||||
#define STATUS_SOFT_LIMIT_ERROR 10
|
#define STATUS_SOFT_LIMIT_ERROR 10
|
||||||
#define STATUS_OVERFLOW 11
|
#define STATUS_OVERFLOW 11
|
||||||
#define STATUS_MAX_STEP_RATE_EXCEEDED 12
|
#define STATUS_MAX_STEP_RATE_EXCEEDED 12
|
||||||
#define STATUS_CHECK_DOOR 13
|
#define STATUS_CHECK_DOOR 13
|
||||||
|
#define STATUS_LINE_LENGTH_EXCEEDED 14
|
||||||
|
#define STATUS_TRAVEL_EXCEEDED 15
|
||||||
|
#define STATUS_INVALID_JOG_COMMAND 16
|
||||||
|
|
||||||
#define STATUS_GCODE_UNSUPPORTED_COMMAND 20
|
#define STATUS_GCODE_UNSUPPORTED_COMMAND 20
|
||||||
#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21
|
#define STATUS_GCODE_MODAL_GROUP_VIOLATION 21
|
||||||
@ -55,22 +58,29 @@
|
|||||||
#define STATUS_GCODE_UNUSED_WORDS 36
|
#define STATUS_GCODE_UNUSED_WORDS 36
|
||||||
#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
|
#define STATUS_GCODE_G43_DYNAMIC_AXIS_ERROR 37
|
||||||
|
|
||||||
// Define Grbl alarm codes.
|
// Define Grbl alarm codes. Valid values (1-255). 0 is reserved.
|
||||||
#define ALARM_HARD_LIMIT_ERROR 1
|
#define ALARM_HARD_LIMIT_ERROR EXEC_ALARM_HARD_LIMIT
|
||||||
#define ALARM_SOFT_LIMIT_ERROR 2
|
#define ALARM_SOFT_LIMIT_ERROR EXEC_ALARM_SOFT_LIMIT
|
||||||
#define ALARM_ABORT_CYCLE 3
|
#define ALARM_ABORT_CYCLE EXEC_ALARM_ABORT_CYCLE
|
||||||
#define ALARM_PROBE_FAIL 4
|
#define ALARM_PROBE_FAIL_INITIAL EXEC_ALARM_PROBE_FAIL_INITIAL
|
||||||
#define ALARM_HOMING_FAIL 5
|
#define ALARM_PROBE_FAIL_CONTACT EXEC_ALARM_PROBE_FAIL_CONTACT
|
||||||
|
#define ALARM_HOMING_FAIL_RESET EXEC_ALARM_HOMING_FAIL_RESET
|
||||||
|
#define ALARM_HOMING_FAIL_DOOR EXEC_ALARM_HOMING_FAIL_DOOR
|
||||||
|
#define ALARM_HOMING_FAIL_PULLOFF EXEC_ALARM_HOMING_FAIL_PULLOFF
|
||||||
|
#define ALARM_HOMING_FAIL_APPROACH EXEC_ALARM_HOMING_FAIL_APPROACH
|
||||||
|
|
||||||
// Define Grbl feedback message codes.
|
// Define Grbl feedback message codes. Valid values (0-255).
|
||||||
#define MESSAGE_CRITICAL_EVENT 1
|
#define MESSAGE_CRITICAL_EVENT 1
|
||||||
#define MESSAGE_ALARM_LOCK 2
|
#define MESSAGE_ALARM_LOCK 2
|
||||||
#define MESSAGE_ALARM_UNLOCK 3
|
#define MESSAGE_ALARM_UNLOCK 3
|
||||||
#define MESSAGE_ENABLED 4
|
#define MESSAGE_ENABLED 4
|
||||||
#define MESSAGE_DISABLED 5
|
#define MESSAGE_DISABLED 5
|
||||||
#define MESSAGE_SAFETY_DOOR_AJAR 6
|
#define MESSAGE_SAFETY_DOOR_AJAR 6
|
||||||
#define MESSAGE_PROGRAM_END 7
|
#define MESSAGE_CHECK_LIMITS 7
|
||||||
#define MESSAGE_RESTORE_DEFAULTS 8
|
#define MESSAGE_PROGRAM_END 8
|
||||||
|
#define MESSAGE_RESTORE_DEFAULTS 9
|
||||||
|
#define MESSAGE_SPINDLE_RESTORE 10
|
||||||
|
#define MESSAGE_SLEEP_MODE 11
|
||||||
|
|
||||||
// Prints system status messages.
|
// Prints system status messages.
|
||||||
void report_status_message(uint8_t status_code);
|
void report_status_message(uint8_t status_code);
|
||||||
@ -105,10 +115,15 @@ void report_ngc_parameters();
|
|||||||
// Prints current g-code parser mode state
|
// Prints current g-code parser mode state
|
||||||
void report_gcode_modes();
|
void report_gcode_modes();
|
||||||
|
|
||||||
// Prints startup line
|
// Prints startup line when requested and executed.
|
||||||
void report_startup_line(uint8_t n, char *line);
|
void report_startup_line(uint8_t n, char *line);
|
||||||
|
void report_execute_startup_message(char *line, uint8_t status_code);
|
||||||
|
|
||||||
// Prints build info and user info
|
// Prints build info and user info
|
||||||
void report_build_info(char *line);
|
void report_build_info(char *line);
|
||||||
|
|
||||||
|
#ifdef DEBUG
|
||||||
|
void report_realtime_debug();
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
159
grbl/serial.c
159
grbl/serial.c
@ -2,7 +2,7 @@
|
|||||||
serial.c - Low level functions for sending and recieving bytes via the serial port
|
serial.c - Low level functions for sending and recieving bytes via the serial port
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -21,22 +21,29 @@
|
|||||||
|
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
|
|
||||||
|
#define RX_RING_BUFFER (RX_BUFFER_SIZE+1)
|
||||||
|
#define TX_RING_BUFFER (TX_BUFFER_SIZE+1)
|
||||||
|
|
||||||
uint8_t serial_rx_buffer[RX_BUFFER_SIZE];
|
uint8_t serial_rx_buffer[RX_RING_BUFFER];
|
||||||
uint8_t serial_rx_buffer_head = 0;
|
uint8_t serial_rx_buffer_head = 0;
|
||||||
volatile uint8_t serial_rx_buffer_tail = 0;
|
volatile uint8_t serial_rx_buffer_tail = 0;
|
||||||
|
|
||||||
uint8_t serial_tx_buffer[TX_BUFFER_SIZE];
|
uint8_t serial_tx_buffer[TX_RING_BUFFER];
|
||||||
uint8_t serial_tx_buffer_head = 0;
|
uint8_t serial_tx_buffer_head = 0;
|
||||||
volatile uint8_t serial_tx_buffer_tail = 0;
|
volatile uint8_t serial_tx_buffer_tail = 0;
|
||||||
|
|
||||||
|
|
||||||
#ifdef ENABLE_XONXOFF
|
// Returns the number of bytes available in the RX serial buffer.
|
||||||
volatile uint8_t flow_ctrl = XON_SENT; // Flow control state variable
|
uint8_t serial_get_rx_buffer_available()
|
||||||
#endif
|
{
|
||||||
|
uint8_t rtail = serial_rx_buffer_tail; // Copy to limit multiple calls to volatile
|
||||||
|
if (serial_rx_buffer_head >= rtail) { return(RX_BUFFER_SIZE - (serial_rx_buffer_head-rtail)); }
|
||||||
|
return((rtail-serial_rx_buffer_head-1));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// Returns the number of bytes used in the RX serial buffer.
|
// Returns the number of bytes used in the RX serial buffer.
|
||||||
|
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h.
|
||||||
uint8_t serial_get_rx_buffer_count()
|
uint8_t serial_get_rx_buffer_count()
|
||||||
{
|
{
|
||||||
uint8_t rtail = serial_rx_buffer_tail; // Copy to limit multiple calls to volatile
|
uint8_t rtail = serial_rx_buffer_tail; // Copy to limit multiple calls to volatile
|
||||||
@ -51,7 +58,7 @@ uint8_t serial_get_tx_buffer_count()
|
|||||||
{
|
{
|
||||||
uint8_t ttail = serial_tx_buffer_tail; // Copy to limit multiple calls to volatile
|
uint8_t ttail = serial_tx_buffer_tail; // Copy to limit multiple calls to volatile
|
||||||
if (serial_tx_buffer_head >= ttail) { return(serial_tx_buffer_head-ttail); }
|
if (serial_tx_buffer_head >= ttail) { return(serial_tx_buffer_head-ttail); }
|
||||||
return (TX_BUFFER_SIZE - (ttail-serial_tx_buffer_head));
|
return (TX_RING_BUFFER - (ttail-serial_tx_buffer_head));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -67,37 +74,32 @@ void serial_init()
|
|||||||
#endif
|
#endif
|
||||||
UBRR0H = UBRR0_value >> 8;
|
UBRR0H = UBRR0_value >> 8;
|
||||||
UBRR0L = UBRR0_value;
|
UBRR0L = UBRR0_value;
|
||||||
|
|
||||||
// enable rx and tx
|
// enable rx, tx, and interrupt on complete reception of a byte
|
||||||
UCSR0B |= 1<<RXEN0;
|
UCSR0B |= (1<<RXEN0 | 1<<TXEN0 | 1<<RXCIE0);
|
||||||
UCSR0B |= 1<<TXEN0;
|
|
||||||
|
|
||||||
// enable interrupt on complete reception of a byte
|
|
||||||
UCSR0B |= 1<<RXCIE0;
|
|
||||||
|
|
||||||
// defaults to 8-bit, no parity, 1 stop bit
|
// defaults to 8-bit, no parity, 1 stop bit
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Writes one byte to the TX serial buffer. Called by main program.
|
// Writes one byte to the TX serial buffer. Called by main program.
|
||||||
// TODO: Check if we can speed this up for writing strings, rather than single bytes.
|
|
||||||
void serial_write(uint8_t data) {
|
void serial_write(uint8_t data) {
|
||||||
// Calculate next head
|
// Calculate next head
|
||||||
uint8_t next_head = serial_tx_buffer_head + 1;
|
uint8_t next_head = serial_tx_buffer_head + 1;
|
||||||
if (next_head == TX_BUFFER_SIZE) { next_head = 0; }
|
if (next_head == TX_RING_BUFFER) { next_head = 0; }
|
||||||
|
|
||||||
// Wait until there is space in the buffer
|
// Wait until there is space in the buffer
|
||||||
while (next_head == serial_tx_buffer_tail) {
|
while (next_head == serial_tx_buffer_tail) {
|
||||||
// TODO: Restructure st_prep_buffer() calls to be executed here during a long print.
|
// TODO: Restructure st_prep_buffer() calls to be executed here during a long print.
|
||||||
if (sys_rt_exec_state & EXEC_RESET) { return; } // Only check for abort to avoid an endless loop.
|
if (sys_rt_exec_state & EXEC_RESET) { return; } // Only check for abort to avoid an endless loop.
|
||||||
}
|
}
|
||||||
|
|
||||||
// Store data and advance head
|
// Store data and advance head
|
||||||
serial_tx_buffer[serial_tx_buffer_head] = data;
|
serial_tx_buffer[serial_tx_buffer_head] = data;
|
||||||
serial_tx_buffer_head = next_head;
|
serial_tx_buffer_head = next_head;
|
||||||
|
|
||||||
// Enable Data Register Empty Interrupt to make sure tx-streaming is running
|
// Enable Data Register Empty Interrupt to make sure tx-streaming is running
|
||||||
UCSR0B |= (1 << UDRIE0);
|
UCSR0B |= (1 << UDRIE0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -105,27 +107,16 @@ void serial_write(uint8_t data) {
|
|||||||
ISR(SERIAL_UDRE)
|
ISR(SERIAL_UDRE)
|
||||||
{
|
{
|
||||||
uint8_t tail = serial_tx_buffer_tail; // Temporary serial_tx_buffer_tail (to optimize for volatile)
|
uint8_t tail = serial_tx_buffer_tail; // Temporary serial_tx_buffer_tail (to optimize for volatile)
|
||||||
|
|
||||||
#ifdef ENABLE_XONXOFF
|
// Send a byte from the buffer
|
||||||
if (flow_ctrl == SEND_XOFF) {
|
UDR0 = serial_tx_buffer[tail];
|
||||||
UDR0 = XOFF_CHAR;
|
|
||||||
flow_ctrl = XOFF_SENT;
|
// Update tail position
|
||||||
} else if (flow_ctrl == SEND_XON) {
|
tail++;
|
||||||
UDR0 = XON_CHAR;
|
if (tail == TX_RING_BUFFER) { tail = 0; }
|
||||||
flow_ctrl = XON_SENT;
|
|
||||||
} else
|
serial_tx_buffer_tail = tail;
|
||||||
#endif
|
|
||||||
{
|
|
||||||
// Send a byte from the buffer
|
|
||||||
UDR0 = serial_tx_buffer[tail];
|
|
||||||
|
|
||||||
// Update tail position
|
|
||||||
tail++;
|
|
||||||
if (tail == TX_BUFFER_SIZE) { tail = 0; }
|
|
||||||
|
|
||||||
serial_tx_buffer_tail = tail;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Turn off Data Register Empty Interrupt to stop tx-streaming if this concludes the transfer
|
// Turn off Data Register Empty Interrupt to stop tx-streaming if this concludes the transfer
|
||||||
if (tail == serial_tx_buffer_head) { UCSR0B &= ~(1 << UDRIE0); }
|
if (tail == serial_tx_buffer_head) { UCSR0B &= ~(1 << UDRIE0); }
|
||||||
}
|
}
|
||||||
@ -139,18 +130,11 @@ uint8_t serial_read()
|
|||||||
return SERIAL_NO_DATA;
|
return SERIAL_NO_DATA;
|
||||||
} else {
|
} else {
|
||||||
uint8_t data = serial_rx_buffer[tail];
|
uint8_t data = serial_rx_buffer[tail];
|
||||||
|
|
||||||
tail++;
|
tail++;
|
||||||
if (tail == RX_BUFFER_SIZE) { tail = 0; }
|
if (tail == RX_RING_BUFFER) { tail = 0; }
|
||||||
serial_rx_buffer_tail = tail;
|
serial_rx_buffer_tail = tail;
|
||||||
|
|
||||||
#ifdef ENABLE_XONXOFF
|
|
||||||
if ((serial_get_rx_buffer_count() < RX_BUFFER_LOW) && flow_ctrl == XOFF_SENT) {
|
|
||||||
flow_ctrl = SEND_XON;
|
|
||||||
UCSR0B |= (1 << UDRIE0); // Force TX
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return data;
|
return data;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -160,42 +144,61 @@ ISR(SERIAL_RX)
|
|||||||
{
|
{
|
||||||
uint8_t data = UDR0;
|
uint8_t data = UDR0;
|
||||||
uint8_t next_head;
|
uint8_t next_head;
|
||||||
|
|
||||||
// Pick off realtime command characters directly from the serial stream. These characters are
|
// Pick off realtime command characters directly from the serial stream. These characters are
|
||||||
// not passed into the buffer, but these set system state flag bits for realtime execution.
|
// not passed into the main buffer, but these set system state flag bits for realtime execution.
|
||||||
switch (data) {
|
switch (data) {
|
||||||
|
case CMD_RESET: mc_reset(); break; // Call motion control reset routine.
|
||||||
case CMD_STATUS_REPORT: system_set_exec_state_flag(EXEC_STATUS_REPORT); break; // Set as true
|
case CMD_STATUS_REPORT: system_set_exec_state_flag(EXEC_STATUS_REPORT); break; // Set as true
|
||||||
case CMD_CYCLE_START: system_set_exec_state_flag(EXEC_CYCLE_START); break; // Set as true
|
case CMD_CYCLE_START: system_set_exec_state_flag(EXEC_CYCLE_START); break; // Set as true
|
||||||
case CMD_FEED_HOLD: system_set_exec_state_flag(EXEC_FEED_HOLD); break; // Set as true
|
case CMD_FEED_HOLD: system_set_exec_state_flag(EXEC_FEED_HOLD); break; // Set as true
|
||||||
case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true
|
default :
|
||||||
case CMD_RESET: mc_reset(); break; // Call motion control reset routine.
|
if (data > 0x7F) { // Real-time control characters are extended ACSII only.
|
||||||
default: // Write character to buffer
|
switch(data) {
|
||||||
next_head = serial_rx_buffer_head + 1;
|
case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true
|
||||||
if (next_head == RX_BUFFER_SIZE) { next_head = 0; }
|
case CMD_JOG_CANCEL:
|
||||||
|
if (sys.state & STATE_JOG) { // Block all other states from invoking motion cancel.
|
||||||
// Write data to buffer unless it is full.
|
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
|
||||||
if (next_head != serial_rx_buffer_tail) {
|
}
|
||||||
serial_rx_buffer[serial_rx_buffer_head] = data;
|
break;
|
||||||
serial_rx_buffer_head = next_head;
|
#ifdef DEBUG
|
||||||
|
case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug,EXEC_DEBUG_REPORT); SREG = sreg;} break;
|
||||||
#ifdef ENABLE_XONXOFF
|
#endif
|
||||||
if ((serial_get_rx_buffer_count() >= RX_BUFFER_FULL) && flow_ctrl == XON_SENT) {
|
case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break;
|
||||||
flow_ctrl = SEND_XOFF;
|
case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break;
|
||||||
UCSR0B |= (1 << UDRIE0); // Force TX
|
case CMD_FEED_OVR_COARSE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_MINUS); break;
|
||||||
}
|
case CMD_FEED_OVR_FINE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_PLUS); break;
|
||||||
#endif
|
case CMD_FEED_OVR_FINE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_MINUS); break;
|
||||||
|
case CMD_RAPID_OVR_RESET: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_RESET); break;
|
||||||
|
case CMD_RAPID_OVR_MEDIUM: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_MEDIUM); break;
|
||||||
|
case CMD_RAPID_OVR_LOW: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_LOW); break;
|
||||||
|
case CMD_SPINDLE_OVR_RESET: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_RESET); break;
|
||||||
|
case CMD_SPINDLE_OVR_COARSE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
|
||||||
|
case CMD_SPINDLE_OVR_COARSE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
|
||||||
|
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
|
||||||
|
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
|
||||||
|
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
|
||||||
|
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
|
||||||
|
#ifdef ENABLE_M7
|
||||||
|
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
// Throw away any unfound extended-ASCII character by not passing it to the serial buffer.
|
||||||
|
} else { // Write character to buffer
|
||||||
|
next_head = serial_rx_buffer_head + 1;
|
||||||
|
if (next_head == RX_RING_BUFFER) { next_head = 0; }
|
||||||
|
|
||||||
|
// Write data to buffer unless it is full.
|
||||||
|
if (next_head != serial_rx_buffer_tail) {
|
||||||
|
serial_rx_buffer[serial_rx_buffer_head] = data;
|
||||||
|
serial_rx_buffer_head = next_head;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
//TODO: else alarm on overflow?
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void serial_reset_read_buffer()
|
void serial_reset_read_buffer()
|
||||||
{
|
{
|
||||||
serial_rx_buffer_tail = serial_rx_buffer_head;
|
serial_rx_buffer_tail = serial_rx_buffer_head;
|
||||||
|
|
||||||
#ifdef ENABLE_XONXOFF
|
|
||||||
flow_ctrl = XON_SENT;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
serial.c - Low level functions for sending and recieving bytes via the serial port
|
serial.c - Low level functions for sending and recieving bytes via the serial port
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -27,21 +27,15 @@
|
|||||||
#define RX_BUFFER_SIZE 128
|
#define RX_BUFFER_SIZE 128
|
||||||
#endif
|
#endif
|
||||||
#ifndef TX_BUFFER_SIZE
|
#ifndef TX_BUFFER_SIZE
|
||||||
#define TX_BUFFER_SIZE 64
|
#ifdef USE_LINE_NUMBERS
|
||||||
|
#define TX_BUFFER_SIZE 100
|
||||||
|
#else
|
||||||
|
#define TX_BUFFER_SIZE 90
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SERIAL_NO_DATA 0xff
|
#define SERIAL_NO_DATA 0xff
|
||||||
|
|
||||||
#ifdef ENABLE_XONXOFF
|
|
||||||
#define RX_BUFFER_FULL 96 // XOFF high watermark
|
|
||||||
#define RX_BUFFER_LOW 64 // XON low watermark
|
|
||||||
#define SEND_XOFF 1
|
|
||||||
#define SEND_XON 2
|
|
||||||
#define XOFF_SENT 3
|
|
||||||
#define XON_SENT 4
|
|
||||||
#define XOFF_CHAR 0x13
|
|
||||||
#define XON_CHAR 0x11
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void serial_init();
|
void serial_init();
|
||||||
|
|
||||||
@ -54,7 +48,11 @@ uint8_t serial_read();
|
|||||||
// Reset and empty data in read buffer. Used by e-stop and reset.
|
// Reset and empty data in read buffer. Used by e-stop and reset.
|
||||||
void serial_reset_read_buffer();
|
void serial_reset_read_buffer();
|
||||||
|
|
||||||
|
// Returns the number of bytes available in the RX serial buffer.
|
||||||
|
uint8_t serial_get_rx_buffer_available();
|
||||||
|
|
||||||
// Returns the number of bytes used in the RX serial buffer.
|
// Returns the number of bytes used in the RX serial buffer.
|
||||||
|
// NOTE: Deprecated. Not used unless classic status reports are enabled in config.h.
|
||||||
uint8_t serial_get_rx_buffer_count();
|
uint8_t serial_get_rx_buffer_count();
|
||||||
|
|
||||||
// Returns the number of bytes used in the TX serial buffer.
|
// Returns the number of bytes used in the TX serial buffer.
|
||||||
|
185
grbl/settings.c
185
grbl/settings.c
@ -1,8 +1,8 @@
|
|||||||
/*
|
/*
|
||||||
settings.c - eeprom configuration handling
|
settings.c - eeprom configuration handling
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -27,95 +27,111 @@ settings_t settings;
|
|||||||
// Method to store startup lines into EEPROM
|
// Method to store startup lines into EEPROM
|
||||||
void settings_store_startup_line(uint8_t n, char *line)
|
void settings_store_startup_line(uint8_t n, char *line)
|
||||||
{
|
{
|
||||||
|
#ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE
|
||||||
|
protocol_buffer_synchronize(); // A startup line may contain a motion and be executing.
|
||||||
|
#endif
|
||||||
uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
uint32_t addr = n*(LINE_BUFFER_SIZE+1)+EEPROM_ADDR_STARTUP_BLOCK;
|
||||||
memcpy_to_eeprom_with_checksum(addr,(char*)line, LINE_BUFFER_SIZE);
|
memcpy_to_eeprom_with_checksum(addr,(char*)line, LINE_BUFFER_SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Method to store build info into EEPROM
|
// Method to store build info into EEPROM
|
||||||
|
// NOTE: This function can only be called in IDLE state.
|
||||||
void settings_store_build_info(char *line)
|
void settings_store_build_info(char *line)
|
||||||
{
|
{
|
||||||
|
// Build info can only be stored when state is IDLE.
|
||||||
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_BUILD_INFO,(char*)line, LINE_BUFFER_SIZE);
|
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_BUILD_INFO,(char*)line, LINE_BUFFER_SIZE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Method to store coord data parameters into EEPROM
|
// Method to store coord data parameters into EEPROM
|
||||||
void settings_write_coord_data(uint8_t coord_select, float *coord_data)
|
void settings_write_coord_data(uint8_t coord_select, float *coord_data)
|
||||||
{
|
{
|
||||||
|
#ifdef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE
|
||||||
|
protocol_buffer_synchronize();
|
||||||
|
#endif
|
||||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||||
memcpy_to_eeprom_with_checksum(addr,(char*)coord_data, sizeof(float)*N_AXIS);
|
memcpy_to_eeprom_with_checksum(addr,(char*)coord_data, sizeof(float)*N_AXIS);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Method to store Grbl global settings struct and version number into EEPROM
|
// Method to store Grbl global settings struct and version number into EEPROM
|
||||||
void write_global_settings()
|
// NOTE: This function can only be called in IDLE state.
|
||||||
|
void write_global_settings()
|
||||||
{
|
{
|
||||||
eeprom_put_char(0, SETTINGS_VERSION);
|
eeprom_put_char(0, SETTINGS_VERSION);
|
||||||
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_GLOBAL, (char*)&settings, sizeof(settings_t));
|
memcpy_to_eeprom_with_checksum(EEPROM_ADDR_GLOBAL, (char*)&settings, sizeof(settings_t));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Method to restore EEPROM-saved Grbl global settings back to defaults.
|
// Method to restore EEPROM-saved Grbl global settings back to defaults.
|
||||||
void settings_restore(uint8_t restore_flag) {
|
void settings_restore(uint8_t restore_flag) {
|
||||||
if (restore_flag & SETTINGS_RESTORE_DEFAULTS) {
|
if (restore_flag & SETTINGS_RESTORE_DEFAULTS) {
|
||||||
settings.pulse_microseconds = DEFAULT_STEP_PULSE_MICROSECONDS;
|
settings.pulse_microseconds = DEFAULT_STEP_PULSE_MICROSECONDS;
|
||||||
settings.stepper_idle_lock_time = DEFAULT_STEPPER_IDLE_LOCK_TIME;
|
settings.stepper_idle_lock_time = DEFAULT_STEPPER_IDLE_LOCK_TIME;
|
||||||
settings.step_invert_mask = DEFAULT_STEPPING_INVERT_MASK;
|
settings.step_invert_mask = DEFAULT_STEPPING_INVERT_MASK;
|
||||||
settings.dir_invert_mask = DEFAULT_DIRECTION_INVERT_MASK;
|
settings.dir_invert_mask = DEFAULT_DIRECTION_INVERT_MASK;
|
||||||
settings.status_report_mask = DEFAULT_STATUS_REPORT_MASK;
|
settings.status_report_mask = DEFAULT_STATUS_REPORT_MASK;
|
||||||
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
|
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
|
||||||
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
|
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
|
||||||
|
|
||||||
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
|
|
||||||
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
|
|
||||||
|
|
||||||
settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
|
|
||||||
settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
|
|
||||||
settings.homing_seek_rate = DEFAULT_HOMING_SEEK_RATE;
|
|
||||||
settings.homing_debounce_delay = DEFAULT_HOMING_DEBOUNCE_DELAY;
|
|
||||||
settings.homing_pulloff = DEFAULT_HOMING_PULLOFF;
|
|
||||||
|
|
||||||
settings.flags = 0;
|
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
|
||||||
if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; }
|
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
|
||||||
if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
|
|
||||||
if (DEFAULT_INVERT_LIMIT_PINS) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
|
|
||||||
if (DEFAULT_SOFT_LIMIT_ENABLE) { settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; }
|
|
||||||
if (DEFAULT_HARD_LIMIT_ENABLE) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
|
|
||||||
if (DEFAULT_HOMING_ENABLE) { settings.flags |= BITFLAG_HOMING_ENABLE; }
|
|
||||||
|
|
||||||
settings.steps_per_mm[X_AXIS] = DEFAULT_X_STEPS_PER_MM;
|
|
||||||
settings.steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM;
|
|
||||||
settings.steps_per_mm[Z_AXIS] = DEFAULT_Z_STEPS_PER_MM;
|
|
||||||
settings.max_rate[X_AXIS] = DEFAULT_X_MAX_RATE;
|
|
||||||
settings.max_rate[Y_AXIS] = DEFAULT_Y_MAX_RATE;
|
|
||||||
settings.max_rate[Z_AXIS] = DEFAULT_Z_MAX_RATE;
|
|
||||||
settings.acceleration[X_AXIS] = DEFAULT_X_ACCELERATION;
|
|
||||||
settings.acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION;
|
|
||||||
settings.acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION;
|
|
||||||
settings.max_travel[X_AXIS] = (-DEFAULT_X_MAX_TRAVEL);
|
|
||||||
settings.max_travel[Y_AXIS] = (-DEFAULT_Y_MAX_TRAVEL);
|
|
||||||
settings.max_travel[Z_AXIS] = (-DEFAULT_Z_MAX_TRAVEL);
|
|
||||||
|
|
||||||
write_global_settings();
|
settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
|
||||||
|
settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
|
||||||
|
settings.homing_seek_rate = DEFAULT_HOMING_SEEK_RATE;
|
||||||
|
settings.homing_debounce_delay = DEFAULT_HOMING_DEBOUNCE_DELAY;
|
||||||
|
settings.homing_pulloff = DEFAULT_HOMING_PULLOFF;
|
||||||
|
|
||||||
|
settings.flags = 0;
|
||||||
|
if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; }
|
||||||
|
if (DEFAULT_LASER_MODE) { settings.flags |= BITFLAG_LASER_MODE; }
|
||||||
|
if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
|
||||||
|
if (DEFAULT_HARD_LIMIT_ENABLE) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
|
||||||
|
if (DEFAULT_HOMING_ENABLE) { settings.flags |= BITFLAG_HOMING_ENABLE; }
|
||||||
|
if (DEFAULT_SOFT_LIMIT_ENABLE) { settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; }
|
||||||
|
if (DEFAULT_INVERT_LIMIT_PINS) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
|
||||||
|
if (DEFAULT_INVERT_PROBE_PIN) { settings.flags |= BITFLAG_INVERT_PROBE_PIN; }
|
||||||
|
|
||||||
|
settings.steps_per_mm[X_AXIS] = DEFAULT_X_STEPS_PER_MM;
|
||||||
|
settings.steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM;
|
||||||
|
settings.steps_per_mm[Z_AXIS] = DEFAULT_Z_STEPS_PER_MM;
|
||||||
|
settings.max_rate[X_AXIS] = DEFAULT_X_MAX_RATE;
|
||||||
|
settings.max_rate[Y_AXIS] = DEFAULT_Y_MAX_RATE;
|
||||||
|
settings.max_rate[Z_AXIS] = DEFAULT_Z_MAX_RATE;
|
||||||
|
settings.acceleration[X_AXIS] = DEFAULT_X_ACCELERATION;
|
||||||
|
settings.acceleration[Y_AXIS] = DEFAULT_Y_ACCELERATION;
|
||||||
|
settings.acceleration[Z_AXIS] = DEFAULT_Z_ACCELERATION;
|
||||||
|
settings.max_travel[X_AXIS] = (-DEFAULT_X_MAX_TRAVEL);
|
||||||
|
settings.max_travel[Y_AXIS] = (-DEFAULT_Y_MAX_TRAVEL);
|
||||||
|
settings.max_travel[Z_AXIS] = (-DEFAULT_Z_MAX_TRAVEL);
|
||||||
|
|
||||||
|
write_global_settings();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (restore_flag & SETTINGS_RESTORE_PARAMETERS) {
|
if (restore_flag & SETTINGS_RESTORE_PARAMETERS) {
|
||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
float coord_data[N_AXIS];
|
float coord_data[N_AXIS];
|
||||||
memset(&coord_data, 0, sizeof(coord_data));
|
memset(&coord_data, 0, sizeof(coord_data));
|
||||||
for (idx=0; idx <= SETTING_INDEX_NCOORD; idx++) { settings_write_coord_data(idx, coord_data); }
|
for (idx=0; idx <= SETTING_INDEX_NCOORD; idx++) { settings_write_coord_data(idx, coord_data); }
|
||||||
}
|
}
|
||||||
|
|
||||||
if (restore_flag & SETTINGS_RESTORE_STARTUP_LINES) {
|
if (restore_flag & SETTINGS_RESTORE_STARTUP_LINES) {
|
||||||
#if N_STARTUP_LINE > 0
|
#if N_STARTUP_LINE > 0
|
||||||
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK, 0);
|
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK, 0);
|
||||||
#endif
|
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+1, 0); // Checksum
|
||||||
#if N_STARTUP_LINE > 1
|
#endif
|
||||||
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+1), 0);
|
#if N_STARTUP_LINE > 1
|
||||||
#endif
|
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+1), 0);
|
||||||
|
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+2), 0); // Checksum
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
if (restore_flag & SETTINGS_RESTORE_BUILD_INFO) {
|
||||||
|
eeprom_put_char(EEPROM_ADDR_BUILD_INFO , 0);
|
||||||
|
eeprom_put_char(EEPROM_ADDR_BUILD_INFO+1 , 0); // Checksum
|
||||||
}
|
}
|
||||||
|
|
||||||
if (restore_flag & SETTINGS_RESTORE_BUILD_INFO) { eeprom_put_char(EEPROM_ADDR_BUILD_INFO , 0); }
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -152,12 +168,12 @@ uint8_t settings_read_coord_data(uint8_t coord_select, float *coord_data)
|
|||||||
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
uint32_t addr = coord_select*(sizeof(float)*N_AXIS+1) + EEPROM_ADDR_PARAMETERS;
|
||||||
if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float)*N_AXIS))) {
|
if (!(memcpy_from_eeprom_with_checksum((char*)coord_data, addr, sizeof(float)*N_AXIS))) {
|
||||||
// Reset with default zero vector
|
// Reset with default zero vector
|
||||||
clear_vector_float(coord_data);
|
clear_vector_float(coord_data);
|
||||||
settings_write_coord_data(coord_select,coord_data);
|
settings_write_coord_data(coord_select,coord_data);
|
||||||
return(false);
|
return(false);
|
||||||
}
|
}
|
||||||
return(true);
|
return(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Reads Grbl global settings struct from EEPROM.
|
// Reads Grbl global settings struct from EEPROM.
|
||||||
@ -170,7 +186,7 @@ uint8_t read_global_settings() {
|
|||||||
return(false);
|
return(false);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
return(false);
|
return(false);
|
||||||
}
|
}
|
||||||
return(true);
|
return(true);
|
||||||
}
|
}
|
||||||
@ -178,7 +194,7 @@ uint8_t read_global_settings() {
|
|||||||
|
|
||||||
// A helper method to set settings from command line
|
// A helper method to set settings from command line
|
||||||
uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
||||||
if (value < 0.0) { return(STATUS_NEGATIVE_VALUE); }
|
if (value < 0.0) { return(STATUS_NEGATIVE_VALUE); }
|
||||||
if (parameter >= AXIS_SETTINGS_START_VAL) {
|
if (parameter >= AXIS_SETTINGS_START_VAL) {
|
||||||
// Store axis configuration. Axis numbering sequence set by AXIS_SETTING defines.
|
// Store axis configuration. Axis numbering sequence set by AXIS_SETTING defines.
|
||||||
// NOTE: Ensure the setting index corresponds to the report.c settings printout.
|
// NOTE: Ensure the setting index corresponds to the report.c settings printout.
|
||||||
@ -215,16 +231,16 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
|||||||
// Store non-axis Grbl settings
|
// Store non-axis Grbl settings
|
||||||
uint8_t int_value = trunc(value);
|
uint8_t int_value = trunc(value);
|
||||||
switch(parameter) {
|
switch(parameter) {
|
||||||
case 0:
|
case 0:
|
||||||
if (int_value < 3) { return(STATUS_SETTING_STEP_PULSE_MIN); }
|
if (int_value < 3) { return(STATUS_SETTING_STEP_PULSE_MIN); }
|
||||||
settings.pulse_microseconds = int_value; break;
|
settings.pulse_microseconds = int_value; break;
|
||||||
case 1: settings.stepper_idle_lock_time = int_value; break;
|
case 1: settings.stepper_idle_lock_time = int_value; break;
|
||||||
case 2:
|
case 2:
|
||||||
settings.step_invert_mask = int_value;
|
settings.step_invert_mask = int_value;
|
||||||
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
||||||
break;
|
break;
|
||||||
case 3:
|
case 3:
|
||||||
settings.dir_invert_mask = int_value;
|
settings.dir_invert_mask = int_value;
|
||||||
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
st_generate_step_dir_invert_masks(); // Regenerate step and direction port invert masks.
|
||||||
break;
|
break;
|
||||||
case 4: // Reset to ensure change. Immediate re-init may cause problems.
|
case 4: // Reset to ensure change. Immediate re-init may cause problems.
|
||||||
@ -238,6 +254,7 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
|||||||
case 6: // Reset to ensure change. Immediate re-init may cause problems.
|
case 6: // Reset to ensure change. Immediate re-init may cause problems.
|
||||||
if (int_value) { settings.flags |= BITFLAG_INVERT_PROBE_PIN; }
|
if (int_value) { settings.flags |= BITFLAG_INVERT_PROBE_PIN; }
|
||||||
else { settings.flags &= ~BITFLAG_INVERT_PROBE_PIN; }
|
else { settings.flags &= ~BITFLAG_INVERT_PROBE_PIN; }
|
||||||
|
probe_configure_invert_mask(false);
|
||||||
break;
|
break;
|
||||||
case 10: settings.status_report_mask = int_value; break;
|
case 10: settings.status_report_mask = int_value; break;
|
||||||
case 11: settings.junction_deviation = value; break;
|
case 11: settings.junction_deviation = value; break;
|
||||||
@ -247,9 +264,9 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
|||||||
else { settings.flags &= ~BITFLAG_REPORT_INCHES; }
|
else { settings.flags &= ~BITFLAG_REPORT_INCHES; }
|
||||||
break;
|
break;
|
||||||
case 20:
|
case 20:
|
||||||
if (int_value) {
|
if (int_value) {
|
||||||
if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) { return(STATUS_SOFT_LIMIT_ERROR); }
|
if (bit_isfalse(settings.flags, BITFLAG_HOMING_ENABLE)) { return(STATUS_SOFT_LIMIT_ERROR); }
|
||||||
settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE;
|
settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE;
|
||||||
} else { settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; }
|
} else { settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; }
|
||||||
break;
|
break;
|
||||||
case 21:
|
case 21:
|
||||||
@ -259,8 +276,8 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
|||||||
break;
|
break;
|
||||||
case 22:
|
case 22:
|
||||||
if (int_value) { settings.flags |= BITFLAG_HOMING_ENABLE; }
|
if (int_value) { settings.flags |= BITFLAG_HOMING_ENABLE; }
|
||||||
else {
|
else {
|
||||||
settings.flags &= ~BITFLAG_HOMING_ENABLE;
|
settings.flags &= ~BITFLAG_HOMING_ENABLE;
|
||||||
settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; // Force disable soft-limits.
|
settings.flags &= ~BITFLAG_SOFT_LIMIT_ENABLE; // Force disable soft-limits.
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -269,9 +286,17 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
|||||||
case 25: settings.homing_seek_rate = value; break;
|
case 25: settings.homing_seek_rate = value; break;
|
||||||
case 26: settings.homing_debounce_delay = int_value; break;
|
case 26: settings.homing_debounce_delay = int_value; break;
|
||||||
case 27: settings.homing_pulloff = value; break;
|
case 27: settings.homing_pulloff = value; break;
|
||||||
case 30: settings.rpm_max = value; break;
|
case 30: settings.rpm_max = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
||||||
case 31: settings.rpm_min = value; break;
|
case 31: settings.rpm_min = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
||||||
default:
|
case 32:
|
||||||
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
if (int_value) { settings.flags |= BITFLAG_LASER_MODE; }
|
||||||
|
else { settings.flags &= ~BITFLAG_LASER_MODE; }
|
||||||
|
#else
|
||||||
|
return(STATUS_SETTING_DISABLED);
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
default:
|
||||||
return(STATUS_INVALID_STATEMENT);
|
return(STATUS_INVALID_STATEMENT);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -287,18 +312,6 @@ void settings_init() {
|
|||||||
settings_restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
|
settings_restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
|
||||||
report_grbl_settings();
|
report_grbl_settings();
|
||||||
}
|
}
|
||||||
|
|
||||||
// NOTE: Checking paramater data, startup lines, and build info string should be done here,
|
|
||||||
// but it seems fairly redundant. Each of these can be manually checked and reset or restored.
|
|
||||||
// Check all parameter data into a dummy variable. If error, reset to zero, otherwise do nothing.
|
|
||||||
// float coord_data[N_AXIS];
|
|
||||||
// uint8_t i;
|
|
||||||
// for (i=0; i<=SETTING_INDEX_NCOORD; i++) {
|
|
||||||
// if (!settings_read_coord_data(i, coord_data)) {
|
|
||||||
// report_status_message(STATUS_SETTING_READ_FAIL);
|
|
||||||
// }
|
|
||||||
// }
|
|
||||||
// NOTE: Startup lines are checked and executed by protocol_main_loop at the end of initialization.
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,10 +1,10 @@
|
|||||||
/*
|
/*
|
||||||
settings.h - eeprom configuration handling
|
settings.h - eeprom configuration handling
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
the Free Software Foundation, either version 3 of the License, or
|
the Free Software Foundation, either version 3 of the License, or
|
||||||
@ -31,7 +31,7 @@
|
|||||||
|
|
||||||
// Define bit flag masks for the boolean settings in settings.flag.
|
// Define bit flag masks for the boolean settings in settings.flag.
|
||||||
#define BITFLAG_REPORT_INCHES bit(0)
|
#define BITFLAG_REPORT_INCHES bit(0)
|
||||||
// #define BITFLAG_AUTO_START bit(1) // Obsolete. Don't alter to keep back compatibility.
|
#define BITFLAG_LASER_MODE bit(1)
|
||||||
#define BITFLAG_INVERT_ST_ENABLE bit(2)
|
#define BITFLAG_INVERT_ST_ENABLE bit(2)
|
||||||
#define BITFLAG_HARD_LIMIT_ENABLE bit(3)
|
#define BITFLAG_HARD_LIMIT_ENABLE bit(3)
|
||||||
#define BITFLAG_HOMING_ENABLE bit(4)
|
#define BITFLAG_HOMING_ENABLE bit(4)
|
||||||
@ -40,24 +40,32 @@
|
|||||||
#define BITFLAG_INVERT_PROBE_PIN bit(7)
|
#define BITFLAG_INVERT_PROBE_PIN bit(7)
|
||||||
|
|
||||||
// Define status reporting boolean enable bit flags in settings.status_report_mask
|
// Define status reporting boolean enable bit flags in settings.status_report_mask
|
||||||
#define BITFLAG_RT_STATUS_MACHINE_POSITION bit(0)
|
#ifdef USE_CLASSIC_REALTIME_REPORT
|
||||||
#define BITFLAG_RT_STATUS_WORK_POSITION bit(1)
|
#define BITFLAG_RT_STATUS_MACHINE_POSITION bit(0)
|
||||||
#define BITFLAG_RT_STATUS_PLANNER_BUFFER bit(2)
|
#define BITFLAG_RT_STATUS_WORK_POSITION bit(1)
|
||||||
#define BITFLAG_RT_STATUS_SERIAL_RX bit(3)
|
#define BITFLAG_RT_STATUS_PLANNER_BUFFER bit(2)
|
||||||
#define BITFLAG_RT_STATUS_LIMIT_PINS bit(4)
|
#define BITFLAG_RT_STATUS_SERIAL_RX bit(3)
|
||||||
#define BITFLAG_RT_STATUS_PROBE_PIN bit(5)
|
#define BITFLAG_RT_STATUS_LIMIT_PINS bit(4)
|
||||||
#define BITFLAG_RT_STATUS_CONTROL_PINS bit(6)
|
#define BITFLAG_RT_STATUS_PROBE_PIN bit(5)
|
||||||
|
#define BITFLAG_RT_STATUS_CONTROL_PINS bit(6)
|
||||||
|
#define BITFLAG_RT_STATUS_OVERRIDES bit(7)
|
||||||
|
#else
|
||||||
|
#define BITFLAG_RT_STATUS_POSITION_TYPE bit(0)
|
||||||
|
#define BITFLAG_RT_STATUS_BUFFER_STATE bit(1)
|
||||||
|
#endif
|
||||||
|
|
||||||
// Define settings restore bitflags.
|
// Define settings restore bitflags.
|
||||||
#define SETTINGS_RESTORE_ALL 0xFF // All bitflags
|
|
||||||
#define SETTINGS_RESTORE_DEFAULTS bit(0)
|
#define SETTINGS_RESTORE_DEFAULTS bit(0)
|
||||||
#define SETTINGS_RESTORE_PARAMETERS bit(1)
|
#define SETTINGS_RESTORE_PARAMETERS bit(1)
|
||||||
#define SETTINGS_RESTORE_STARTUP_LINES bit(2)
|
#define SETTINGS_RESTORE_STARTUP_LINES bit(2)
|
||||||
#define SETTINGS_RESTORE_BUILD_INFO bit(3)
|
#define SETTINGS_RESTORE_BUILD_INFO bit(3)
|
||||||
|
#ifndef SETTINGS_RESTORE_ALL
|
||||||
|
#define SETTINGS_RESTORE_ALL 0xFF // All bitflags
|
||||||
|
#endif
|
||||||
|
|
||||||
// Define EEPROM memory address location values for Grbl settings and parameters
|
// Define EEPROM memory address location values for Grbl settings and parameters
|
||||||
// NOTE: The Atmega328p has 1KB EEPROM. The upper half is reserved for parameters and
|
// NOTE: The Atmega328p has 1KB EEPROM. The upper half is reserved for parameters and
|
||||||
// the startup script. The lower half contains the global settings and space for future
|
// the startup script. The lower half contains the global settings and space for future
|
||||||
// developments.
|
// developments.
|
||||||
#define EEPROM_ADDR_GLOBAL 1U
|
#define EEPROM_ADDR_GLOBAL 1U
|
||||||
#define EEPROM_ADDR_PARAMETERS 512U
|
#define EEPROM_ADDR_PARAMETERS 512U
|
||||||
@ -93,10 +101,10 @@ typedef struct {
|
|||||||
uint8_t status_report_mask; // Mask to indicate desired report data.
|
uint8_t status_report_mask; // Mask to indicate desired report data.
|
||||||
float junction_deviation;
|
float junction_deviation;
|
||||||
float arc_tolerance;
|
float arc_tolerance;
|
||||||
|
|
||||||
float rpm_max;
|
float rpm_max;
|
||||||
float rpm_min;
|
float rpm_min;
|
||||||
|
|
||||||
uint8_t flags; // Contains default boolean settings
|
uint8_t flags; // Contains default boolean settings
|
||||||
|
|
||||||
uint8_t homing_dir_mask;
|
uint8_t homing_dir_mask;
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
spindle_control.c - spindle control methods
|
spindle_control.c - spindle control methods
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -22,8 +22,20 @@
|
|||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
|
|
||||||
|
|
||||||
|
#ifdef SPINDLE_MINIMUM_PWM
|
||||||
|
#define SPINDLE_PWM_MIN_VALUE SPINDLE_MINIMUM_PWM
|
||||||
|
#else
|
||||||
|
#define SPINDLE_PWM_MIN_VALUE 0.0
|
||||||
|
#endif
|
||||||
|
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
|
||||||
|
|
||||||
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
void spindle_init()
|
void spindle_init()
|
||||||
{
|
{
|
||||||
#ifdef VARIABLE_SPINDLE
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
|
||||||
// Configure variable spindle PWM and enable pin, if requried. On the Uno, PWM and enable are
|
// Configure variable spindle PWM and enable pin, if requried. On the Uno, PWM and enable are
|
||||||
@ -33,28 +45,32 @@ void spindle_init()
|
|||||||
SPINDLE_TCCRB_REGISTER = SPINDLE_TCCRB_INIT_MASK;
|
SPINDLE_TCCRB_REGISTER = SPINDLE_TCCRB_INIT_MASK;
|
||||||
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||||
SPINDLE_ENABLE_DDR |= (1<<SPINDLE_ENABLE_BIT); // Configure as output pin.
|
SPINDLE_ENABLE_DDR |= (1<<SPINDLE_ENABLE_BIT); // Configure as output pin.
|
||||||
#else
|
#else
|
||||||
SPINDLE_DIRECTION_DDR |= (1<<SPINDLE_DIRECTION_BIT); // Configure as output pin.
|
SPINDLE_DIRECTION_DDR |= (1<<SPINDLE_DIRECTION_BIT); // Configure as output pin.
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#else
|
pwm_gradient = SPINDLE_PWM_RANGE/(settings.rpm_max-settings.rpm_min);
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
// Configure no variable spindle and only enable pin.
|
// Configure no variable spindle and only enable pin.
|
||||||
SPINDLE_ENABLE_DDR |= (1<<SPINDLE_ENABLE_BIT); // Configure as output pin.
|
SPINDLE_ENABLE_DDR |= (1<<SPINDLE_ENABLE_BIT); // Configure as output pin.
|
||||||
SPINDLE_DIRECTION_DDR |= (1<<SPINDLE_DIRECTION_BIT); // Configure as output pin.
|
SPINDLE_DIRECTION_DDR |= (1<<SPINDLE_DIRECTION_BIT); // Configure as output pin.
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spindle_stop();
|
spindle_stop();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Stop and start spindle routines. Called by all spindle routines and various interrupts.
|
||||||
|
// Keep routine small, fast, and efficient.
|
||||||
void spindle_stop()
|
void spindle_stop()
|
||||||
{
|
{
|
||||||
// On the Uno, spindle enable and PWM are shared. Other CPUs have seperate enable pin.
|
// On the Uno, spindle enable and PWM are shared. Other CPUs have seperate enable pin.
|
||||||
#ifdef VARIABLE_SPINDLE
|
#ifdef VARIABLE_SPINDLE
|
||||||
SPINDLE_TCCRA_REGISTER &= ~(1<<SPINDLE_COMB_BIT); // Disable PWM. Output voltage is zero.
|
SPINDLE_TCCRA_REGISTER &= ~(1<<SPINDLE_COMB_BIT); // Disable PWM. Output voltage is zero.
|
||||||
#if defined(CPU_MAP_ATMEGA2560) || defined(USE_SPINDLE_DIR_AS_ENABLE_PIN)
|
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||||
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT); // Set pin to high
|
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT); // Set pin to high
|
||||||
#else
|
#else
|
||||||
@ -67,15 +83,55 @@ void spindle_stop()
|
|||||||
#else
|
#else
|
||||||
SPINDLE_ENABLE_PORT &= ~(1<<SPINDLE_ENABLE_BIT); // Set pin to low
|
SPINDLE_ENABLE_PORT &= ~(1<<SPINDLE_ENABLE_BIT); // Set pin to low
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void spindle_set_state(uint8_t state, float rpm)
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
// Called by spindle state functions and stepper ISR. Keep routine small, fast, and efficient.
|
||||||
|
void spindle_set_speed(uint8_t pwm_value)
|
||||||
|
{
|
||||||
|
if (pwm_value == SPINDLE_PWM_OFF_VALUE) {
|
||||||
|
spindle_stop();
|
||||||
|
} else {
|
||||||
|
SPINDLE_OCR_REGISTER = pwm_value; // Set PWM output level.
|
||||||
|
SPINDLE_TCCRA_REGISTER |= (1<<SPINDLE_COMB_BIT); // Ensure PWM output is enabled.
|
||||||
|
|
||||||
|
#if defined(USE_SPINDLE_DIR_AS_ENABLE_PIN)
|
||||||
|
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||||
|
SPINDLE_ENABLE_PORT &= ~(1<<SPINDLE_ENABLE_BIT);
|
||||||
|
#else
|
||||||
|
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Called by spindle state functions and step segment generator.
|
||||||
|
uint8_t spindle_compute_pwm_value(float rpm) // 328p PWM register is 8-bit.
|
||||||
|
{
|
||||||
|
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
||||||
|
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
|
||||||
|
// No PWM range possible. Set simple on/off spindle control pin state.
|
||||||
|
return(SPINDLE_PWM_MAX_VALUE);
|
||||||
|
} else if (rpm < settings.rpm_min) {
|
||||||
|
if (rpm == 0.0) { return(SPINDLE_PWM_OFF_VALUE); }
|
||||||
|
else { return(SPINDLE_PWM_MIN_VALUE); }
|
||||||
|
} else {
|
||||||
|
return(floor( (rpm-settings.rpm_min)*pwm_gradient + (SPINDLE_PWM_MIN_VALUE+0.5)));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled.
|
||||||
|
// Called by spindle_run() after sync and parking motion/spindle stop override during restore.
|
||||||
|
void spindle_set_state(uint8_t state, uint8_t pwm_value)
|
||||||
{
|
{
|
||||||
if (sys.abort) { return; } // Block during abort.
|
if (sys.abort) { return; } // Block during abort.
|
||||||
|
|
||||||
// Halt or set spindle direction and rpm.
|
// Halt or set spindle direction and rpm.
|
||||||
if (state == SPINDLE_DISABLE) {
|
if (state == SPINDLE_DISABLE) {
|
||||||
|
|
||||||
spindle_stop();
|
spindle_stop();
|
||||||
@ -92,59 +148,32 @@ void spindle_set_state(uint8_t state, float rpm)
|
|||||||
|
|
||||||
#ifdef VARIABLE_SPINDLE
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
|
||||||
// TODO: Install the optional capability for frequency-based output for servos.
|
spindle_set_speed(pwm_value);
|
||||||
uint8_t current_pwm; // 328p PWM register is 8-bit.
|
|
||||||
|
|
||||||
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
|
||||||
if (rpm <= 0.0) { spindle_stop(); } // RPM should never be negative, but check anyway.
|
|
||||||
else {
|
|
||||||
if (settings.rpm_max <= settings.rpm_min) {
|
|
||||||
// No PWM range possible. Set simple on/off spindle control pin state.
|
|
||||||
current_pwm = SPINDLE_PWM_MAX_VALUE;
|
|
||||||
} else {
|
|
||||||
if (rpm > settings.rpm_max) { rpm = settings.rpm_max; }
|
|
||||||
if (rpm < settings.rpm_min) { rpm = settings.rpm_min; }
|
|
||||||
#ifdef SPINDLE_MINIMUM_PWM
|
|
||||||
float pwm_gradient = (SPINDLE_PWM_MAX_VALUE-SPINDLE_MINIMUM_PWM)/(settings.rpm_max-settings.rpm_min);
|
|
||||||
current_pwm = floor( (rpm-settings.rpm_min)*pwm_gradient + (SPINDLE_MINIMUM_PWM+0.5));
|
|
||||||
#else
|
|
||||||
float pwm_gradient = (SPINDLE_PWM_MAX_VALUE)/(settings.rpm_max-settings.rpm_min);
|
|
||||||
current_pwm = floor( (rpm-settings.rpm_min)*pwm_gradient + 0.5);
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
SPINDLE_OCR_REGISTER = current_pwm; // Set PWM output level.
|
|
||||||
SPINDLE_TCCRA_REGISTER |= (1<<SPINDLE_COMB_BIT); // Ensure PWM output is enabled.
|
|
||||||
|
|
||||||
// On the Uno, spindle enable and PWM are shared, unless otherwise specified.
|
|
||||||
#if defined(USE_SPINDLE_DIR_AS_ENABLE_PIN)
|
|
||||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
|
||||||
SPINDLE_ENABLE_PORT &= ~(1<<SPINDLE_ENABLE_BIT);
|
|
||||||
#else
|
|
||||||
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
// NOTE: Without variable spindle, the enable bit should just turn on or off, regardless
|
// NOTE: Without variable spindle, the enable bit should just turn on or off, regardless
|
||||||
// if the spindle speed value is zero, as its ignored anyhow.
|
// if the spindle speed value is zero, as its ignored anyhow.
|
||||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||||
SPINDLE_ENABLE_PORT &= ~(1<<SPINDLE_ENABLE_BIT);
|
SPINDLE_ENABLE_PORT &= ~(1<<SPINDLE_ENABLE_BIT);
|
||||||
#else
|
#else
|
||||||
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT);
|
SPINDLE_ENABLE_PORT |= (1<<SPINDLE_ENABLE_BIT);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Called by g-code parser when setting spindle state and requires a buffer sync.
|
||||||
void spindle_run(uint8_t state, float rpm)
|
void spindle_run(uint8_t state, float rpm)
|
||||||
{
|
{
|
||||||
if (sys.state == STATE_CHECK_MODE) { return; }
|
if (sys.state == STATE_CHECK_MODE) { return; }
|
||||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||||
spindle_set_state(state, rpm);
|
#ifdef VARIABLE_SPINDLE
|
||||||
|
spindle_set_state(state, spindle_compute_pwm_value(rpm));
|
||||||
|
#else
|
||||||
|
spindle_set_state(state,0); // Send null pwm value. Not used.
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -2,7 +2,7 @@
|
|||||||
spindle_control.h - spindle control methods
|
spindle_control.h - spindle control methods
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2012-2015 Sungeun K. Jeon
|
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -17,21 +17,27 @@
|
|||||||
|
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef spindle_control_h
|
#ifndef spindle_control_h
|
||||||
#define spindle_control_h
|
#define spindle_control_h
|
||||||
|
|
||||||
|
|
||||||
// Initializes spindle pins and hardware PWM, if enabled.
|
// Initializes spindle pins and hardware PWM, if enabled.
|
||||||
void spindle_init();
|
void spindle_init();
|
||||||
|
|
||||||
// Sets spindle direction and spindle rpm via PWM, if enabled.
|
// Called by g-code parser when setting spindle state and requires a buffer sync.
|
||||||
void spindle_run(uint8_t direction, float rpm);
|
void spindle_run(uint8_t direction, float rpm);
|
||||||
|
|
||||||
void spindle_set_state(uint8_t state, float rpm);
|
// Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled.
|
||||||
|
// Called by spindle_run() after sync and parking motion/spindle stop override during restore.
|
||||||
|
void spindle_set_state(uint8_t state, uint8_t pwm_value);
|
||||||
|
|
||||||
// Kills spindle.
|
// Stop and start spindle routines. Called by all spindle routines and stepper ISR.
|
||||||
void spindle_stop();
|
void spindle_stop();
|
||||||
|
void spindle_set_speed(uint8_t pwm_value); // Variable spindle only.
|
||||||
|
|
||||||
|
uint8_t spindle_compute_pwm_value(float rpm); // 328p PWM register is 8-bit. Variable spindle only.
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
512
grbl/stepper.c
512
grbl/stepper.c
File diff suppressed because it is too large
Load Diff
@ -2,7 +2,7 @@
|
|||||||
stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
|
stepper.h - stepper motor driver: executes motion plans of planner.c using the stepper motors
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2011-2015 Sungeun K. Jeon
|
Copyright (c) 2011-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
Copyright (c) 2009-2011 Simen Svale Skogsrud
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
@ -20,7 +20,7 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef stepper_h
|
#ifndef stepper_h
|
||||||
#define stepper_h
|
#define stepper_h
|
||||||
|
|
||||||
#ifndef SEGMENT_BUFFER_SIZE
|
#ifndef SEGMENT_BUFFER_SIZE
|
||||||
#define SEGMENT_BUFFER_SIZE 6
|
#define SEGMENT_BUFFER_SIZE 6
|
||||||
@ -38,7 +38,7 @@ void st_go_idle();
|
|||||||
// Generate the step and direction port invert masks.
|
// Generate the step and direction port invert masks.
|
||||||
void st_generate_step_dir_invert_masks();
|
void st_generate_step_dir_invert_masks();
|
||||||
|
|
||||||
// Reset the stepper subsystem variables
|
// Reset the stepper subsystem variables
|
||||||
void st_reset();
|
void st_reset();
|
||||||
|
|
||||||
// Changes the run state of the step segment buffer to execute the special parking motion.
|
// Changes the run state of the step segment buffer to execute the special parking motion.
|
||||||
@ -46,7 +46,7 @@ void st_parking_setup_buffer();
|
|||||||
|
|
||||||
// Restores the step segment buffer to the normal run state after a parking motion.
|
// Restores the step segment buffer to the normal run state after a parking motion.
|
||||||
void st_parking_restore_buffer();
|
void st_parking_restore_buffer();
|
||||||
|
|
||||||
// Reloads step segment buffer. Called continuously by realtime execution system.
|
// Reloads step segment buffer. Called continuously by realtime execution system.
|
||||||
void st_prep_buffer();
|
void st_prep_buffer();
|
||||||
|
|
||||||
@ -54,8 +54,6 @@ void st_prep_buffer();
|
|||||||
void st_update_plan_block_parameters();
|
void st_update_plan_block_parameters();
|
||||||
|
|
||||||
// Called by realtime status reporting if realtime rate reporting is enabled in config.h.
|
// Called by realtime status reporting if realtime rate reporting is enabled in config.h.
|
||||||
#ifdef REPORT_REALTIME_RATE
|
|
||||||
float st_get_realtime_rate();
|
float st_get_realtime_rate();
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
237
grbl/system.c
237
grbl/system.c
@ -2,7 +2,7 @@
|
|||||||
system.c - Handles system level commands and real-time processes
|
system.c - Handles system level commands and real-time processes
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2014-2015 Sungeun K. Jeon
|
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -34,7 +34,7 @@ void system_init()
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Returns control pin state as a uint8 bitfield. Each bit indicates the input pin state, where
|
// Returns control pin state as a uint8 bitfield. Each bit indicates the input pin state, where
|
||||||
// triggered is 1 and not triggered is 0. Invert mask is applied. Bitfield organization is
|
// triggered is 1 and not triggered is 0. Invert mask is applied. Bitfield organization is
|
||||||
// defined by the CONTROL_PIN_INDEX in the header file.
|
// defined by the CONTROL_PIN_INDEX in the header file.
|
||||||
uint8_t system_control_get_state()
|
uint8_t system_control_get_state()
|
||||||
@ -57,25 +57,25 @@ uint8_t system_control_get_state()
|
|||||||
|
|
||||||
|
|
||||||
// Pin change interrupt for pin-out commands, i.e. cycle start, feed hold, and reset. Sets
|
// Pin change interrupt for pin-out commands, i.e. cycle start, feed hold, and reset. Sets
|
||||||
// only the realtime command execute variable to have the main program execute these when
|
// only the realtime command execute variable to have the main program execute these when
|
||||||
// its ready. This works exactly like the character-based realtime commands when picked off
|
// its ready. This works exactly like the character-based realtime commands when picked off
|
||||||
// directly from the incoming serial data stream.
|
// directly from the incoming serial data stream.
|
||||||
ISR(CONTROL_INT_vect)
|
ISR(CONTROL_INT_vect)
|
||||||
{
|
{
|
||||||
uint8_t pin = system_control_get_state();
|
uint8_t pin = system_control_get_state();
|
||||||
if (pin) {
|
if (pin) {
|
||||||
if (bit_istrue(pin,CONTROL_PIN_INDEX_RESET)) {
|
if (bit_istrue(pin,CONTROL_PIN_INDEX_RESET)) {
|
||||||
mc_reset();
|
mc_reset();
|
||||||
} else if (bit_istrue(pin,CONTROL_PIN_INDEX_CYCLE_START)) {
|
} else if (bit_istrue(pin,CONTROL_PIN_INDEX_CYCLE_START)) {
|
||||||
bit_true(sys_rt_exec_state, EXEC_CYCLE_START);
|
bit_true(sys_rt_exec_state, EXEC_CYCLE_START);
|
||||||
#ifndef ENABLE_SAFETY_DOOR_INPUT_PIN
|
#ifndef ENABLE_SAFETY_DOOR_INPUT_PIN
|
||||||
} else if (bit_istrue(pin,CONTROL_PIN_INDEX_FEED_HOLD)) {
|
} else if (bit_istrue(pin,CONTROL_PIN_INDEX_FEED_HOLD)) {
|
||||||
bit_true(sys_rt_exec_state, EXEC_FEED_HOLD);
|
bit_true(sys_rt_exec_state, EXEC_FEED_HOLD);
|
||||||
#else
|
#else
|
||||||
} else if (bit_istrue(pin,CONTROL_PIN_INDEX_SAFETY_DOOR)) {
|
} else if (bit_istrue(pin,CONTROL_PIN_INDEX_SAFETY_DOOR)) {
|
||||||
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
bit_true(sys_rt_exec_state, EXEC_SAFETY_DOOR);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -92,40 +92,47 @@ uint8_t system_check_safety_door_ajar()
|
|||||||
|
|
||||||
|
|
||||||
// Executes user startup script, if stored.
|
// Executes user startup script, if stored.
|
||||||
void system_execute_startup(char *line)
|
void system_execute_startup(char *line)
|
||||||
{
|
{
|
||||||
uint8_t n;
|
uint8_t n;
|
||||||
for (n=0; n < N_STARTUP_LINE; n++) {
|
for (n=0; n < N_STARTUP_LINE; n++) {
|
||||||
if (!(settings_read_startup_line(n, line))) {
|
if (!(settings_read_startup_line(n, line))) {
|
||||||
report_status_message(STATUS_SETTING_READ_FAIL);
|
line[0] = 0;
|
||||||
|
report_execute_startup_message(line,STATUS_SETTING_READ_FAIL);
|
||||||
} else {
|
} else {
|
||||||
if (line[0] != 0) {
|
if (line[0] != 0) {
|
||||||
printString(line); // Echo startup line to indicate execution.
|
uint8_t status_code = gc_execute_line(line);
|
||||||
report_status_message(gc_execute_line(line));
|
report_execute_startup_message(line,status_code);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// Directs and executes one line of formatted input from protocol_process. While mostly
|
// Directs and executes one line of formatted input from protocol_process. While mostly
|
||||||
// incoming streaming g-code blocks, this also executes Grbl internal commands, such as
|
// incoming streaming g-code blocks, this also executes Grbl internal commands, such as
|
||||||
// settings, initiating the homing cycle, and toggling switch states. This differs from
|
// settings, initiating the homing cycle, and toggling switch states. This differs from
|
||||||
// the realtime command module by being susceptible to when Grbl is ready to execute the
|
// the realtime command module by being susceptible to when Grbl is ready to execute the
|
||||||
// next line during a cycle, so for switches like block delete, the switch only effects
|
// next line during a cycle, so for switches like block delete, the switch only effects
|
||||||
// the lines that are processed afterward, not necessarily real-time during a cycle,
|
// the lines that are processed afterward, not necessarily real-time during a cycle,
|
||||||
// since there are motions already stored in the buffer. However, this 'lag' should not
|
// since there are motions already stored in the buffer. However, this 'lag' should not
|
||||||
// be an issue, since these commands are not typically used during a cycle.
|
// be an issue, since these commands are not typically used during a cycle.
|
||||||
uint8_t system_execute_line(char *line)
|
uint8_t system_execute_line(char *line)
|
||||||
{
|
{
|
||||||
uint8_t char_counter = 1;
|
uint8_t char_counter = 1;
|
||||||
uint8_t helper_var = 0; // Helper variable
|
uint8_t helper_var = 0; // Helper variable
|
||||||
float parameter, value;
|
float parameter, value;
|
||||||
switch( line[char_counter] ) {
|
switch( line[char_counter] ) {
|
||||||
case 0 : report_grbl_help(); break;
|
case 0 : report_grbl_help(); break;
|
||||||
|
case 'J' : // Jogging
|
||||||
|
// Execute only if in IDLE or JOG states.
|
||||||
|
if (sys.state != STATE_IDLE && sys.state != STATE_JOG) { return(STATUS_IDLE_ERROR); }
|
||||||
|
if(line[2] != '=') { return(STATUS_INVALID_STATEMENT); }
|
||||||
|
return(gc_execute_line(line)); // NOTE: $J= is ignored inside g-code parser and used to detect jog motions.
|
||||||
|
break;
|
||||||
case '$': case 'G': case 'C': case 'X':
|
case '$': case 'G': case 'C': case 'X':
|
||||||
if ( line[(char_counter+1)] != 0 ) { return(STATUS_INVALID_STATEMENT); }
|
if ( line[2] != 0 ) { return(STATUS_INVALID_STATEMENT); }
|
||||||
switch( line[char_counter] ) {
|
switch( line[1] ) {
|
||||||
case '$' : // Prints Grbl settings
|
case '$' : // Prints Grbl settings
|
||||||
if ( sys.state & (STATE_CYCLE | STATE_HOLD) ) { return(STATUS_IDLE_ERROR); } // Block during cycle. Takes too long to print.
|
if ( sys.state & (STATE_CYCLE | STATE_HOLD) ) { return(STATUS_IDLE_ERROR); } // Block during cycle. Takes too long to print.
|
||||||
else { report_grbl_settings(); }
|
else { report_grbl_settings(); }
|
||||||
@ -133,86 +140,83 @@ uint8_t system_execute_line(char *line)
|
|||||||
case 'G' : // Prints gcode parser state
|
case 'G' : // Prints gcode parser state
|
||||||
// TODO: Move this to realtime commands for GUIs to request this data during suspend-state.
|
// TODO: Move this to realtime commands for GUIs to request this data during suspend-state.
|
||||||
report_gcode_modes();
|
report_gcode_modes();
|
||||||
break;
|
break;
|
||||||
case 'C' : // Set check g-code mode [IDLE/CHECK]
|
case 'C' : // Set check g-code mode [IDLE/CHECK]
|
||||||
// Perform reset when toggling off. Check g-code mode should only work if Grbl
|
// Perform reset when toggling off. Check g-code mode should only work if Grbl
|
||||||
// is idle and ready, regardless of alarm locks. This is mainly to keep things
|
// is idle and ready, regardless of alarm locks. This is mainly to keep things
|
||||||
// simple and consistent.
|
// simple and consistent.
|
||||||
if ( sys.state == STATE_CHECK_MODE ) {
|
if ( sys.state == STATE_CHECK_MODE ) {
|
||||||
mc_reset();
|
mc_reset();
|
||||||
report_feedback_message(MESSAGE_DISABLED);
|
report_feedback_message(MESSAGE_DISABLED);
|
||||||
} else {
|
} else {
|
||||||
if (sys.state) { return(STATUS_IDLE_ERROR); } // Requires no alarm mode.
|
if (sys.state) { return(STATUS_IDLE_ERROR); } // Requires no alarm mode.
|
||||||
sys.state = STATE_CHECK_MODE;
|
sys.state = STATE_CHECK_MODE;
|
||||||
report_feedback_message(MESSAGE_ENABLED);
|
report_feedback_message(MESSAGE_ENABLED);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'X' : // Disable alarm lock [ALARM]
|
case 'X' : // Disable alarm lock [ALARM]
|
||||||
if (sys.state == STATE_ALARM) {
|
if (sys.state == STATE_ALARM) {
|
||||||
// Block if safety door is ajar.
|
// Block if safety door is ajar.
|
||||||
if (system_check_safety_door_ajar()) { return(STATUS_CHECK_DOOR); }
|
if (system_check_safety_door_ajar()) { return(STATUS_CHECK_DOOR); }
|
||||||
report_feedback_message(MESSAGE_ALARM_UNLOCK);
|
report_feedback_message(MESSAGE_ALARM_UNLOCK);
|
||||||
sys.state = STATE_IDLE;
|
sys.state = STATE_IDLE;
|
||||||
// Don't run startup script. Prevents stored moves in startup from causing accidents.
|
// Don't run startup script. Prevents stored moves in startup from causing accidents.
|
||||||
} // Otherwise, no effect.
|
} // Otherwise, no effect.
|
||||||
break;
|
break;
|
||||||
// case 'J' : break; // Jogging methods
|
|
||||||
// TODO: Here jogging can be placed for execution as a seperate subprogram. It does not need to be
|
|
||||||
// susceptible to other realtime commands except for e-stop. The jogging function is intended to
|
|
||||||
// be a basic toggle on/off with controlled acceleration and deceleration to prevent skipped
|
|
||||||
// steps. The user would supply the desired feedrate, axis to move, and direction. Toggle on would
|
|
||||||
// start motion and toggle off would initiate a deceleration to stop. One could 'feather' the
|
|
||||||
// motion by repeatedly toggling to slow the motion to the desired location. Location data would
|
|
||||||
// need to be updated real-time and supplied to the user through status queries.
|
|
||||||
// More controlled exact motions can be taken care of by inputting G0 or G1 commands, which are
|
|
||||||
// handled by the planner. It would be possible for the jog subprogram to insert blocks into the
|
|
||||||
// block buffer without having the planner plan them. It would need to manage de/ac-celerations
|
|
||||||
// on its own carefully. This approach could be effective and possibly size/memory efficient.
|
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
default :
|
default :
|
||||||
// Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing)
|
// Block any system command that requires the state as IDLE/ALARM. (i.e. EEPROM, homing)
|
||||||
if ( !(sys.state == STATE_IDLE || sys.state == STATE_ALARM) ) { return(STATUS_IDLE_ERROR); }
|
if ( !(sys.state == STATE_IDLE || sys.state == STATE_ALARM) ) { return(STATUS_IDLE_ERROR); }
|
||||||
switch( line[char_counter] ) {
|
switch( line[1] ) {
|
||||||
case '#' : // Print Grbl NGC parameters
|
case '#' : // Print Grbl NGC parameters
|
||||||
if ( line[++char_counter] != 0 ) { return(STATUS_INVALID_STATEMENT); }
|
if ( line[2] != 0 ) { return(STATUS_INVALID_STATEMENT); }
|
||||||
else { report_ngc_parameters(); }
|
else { report_ngc_parameters(); }
|
||||||
break;
|
break;
|
||||||
case 'H' : // Perform homing cycle [IDLE/ALARM]
|
case 'H' : // Perform homing cycle [IDLE/ALARM]
|
||||||
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
|
if (bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)) {
|
||||||
// Block if safety door is ajar.
|
// Block if safety door is ajar.
|
||||||
if (system_check_safety_door_ajar()) { return(STATUS_CHECK_DOOR); }
|
if (system_check_safety_door_ajar()) { return(STATUS_CHECK_DOOR); }
|
||||||
sys.state = STATE_HOMING; // Set system state variable
|
sys.state = STATE_HOMING; // Set system state variable
|
||||||
mc_homing_cycle();
|
mc_homing_cycle();
|
||||||
if (!sys.abort) { // Execute startup scripts after successful homing.
|
if (!sys.abort) { // Execute startup scripts after successful homing.
|
||||||
sys.state = STATE_IDLE; // Set to IDLE when complete.
|
sys.state = STATE_IDLE; // Set to IDLE when complete.
|
||||||
st_go_idle(); // Set steppers to the settings idle state before returning.
|
st_go_idle(); // Set steppers to the settings idle state before returning.
|
||||||
system_execute_startup(line);
|
system_execute_startup(line);
|
||||||
}
|
}
|
||||||
} else { return(STATUS_SETTING_DISABLED); }
|
} else { return(STATUS_SETTING_DISABLED); }
|
||||||
break;
|
break;
|
||||||
|
case 'S' : // Puts Grbl to sleep [IDLE/ALARM]
|
||||||
|
if ((line[2] != 'L') || (line[3] != 'P') || (line[4] != 0)) { return(STATUS_INVALID_STATEMENT); }
|
||||||
|
system_set_exec_state_flag(EXEC_SLEEP); // Set to execute sleep mode immediately
|
||||||
|
break;
|
||||||
case 'I' : // Print or store build info. [IDLE/ALARM]
|
case 'I' : // Print or store build info. [IDLE/ALARM]
|
||||||
if ( line[++char_counter] == 0 ) {
|
if ( line[++char_counter] == 0 ) {
|
||||||
settings_read_build_info(line);
|
settings_read_build_info(line);
|
||||||
report_build_info(line);
|
report_build_info(line);
|
||||||
} else { // Store startup line [IDLE/ALARM]
|
#ifdef ENABLE_BUILD_INFO_WRITE_COMMAND
|
||||||
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
|
} else { // Store startup line [IDLE/ALARM]
|
||||||
helper_var = char_counter; // Set helper variable as counter to start of user info line.
|
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
|
||||||
do {
|
helper_var = char_counter; // Set helper variable as counter to start of user info line.
|
||||||
line[char_counter-helper_var] = line[char_counter];
|
do {
|
||||||
} while (line[char_counter++] != 0);
|
line[char_counter-helper_var] = line[char_counter];
|
||||||
settings_store_build_info(line);
|
} while (line[char_counter++] != 0);
|
||||||
|
settings_store_build_info(line);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'R' : // Restore defaults [IDLE/ALARM]
|
case 'R' : // Restore defaults [IDLE/ALARM]
|
||||||
if (line[++char_counter] != 'S') { return(STATUS_INVALID_STATEMENT); }
|
if ((line[2] != 'S') || (line[3] != 'T') || (line[4] != '=') || (line[6] != 0)) { return(STATUS_INVALID_STATEMENT); }
|
||||||
if (line[++char_counter] != 'T') { return(STATUS_INVALID_STATEMENT); }
|
switch (line[5]) {
|
||||||
if (line[++char_counter] != '=') { return(STATUS_INVALID_STATEMENT); }
|
#ifdef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS
|
||||||
if (line[char_counter+2] != 0) { return(STATUS_INVALID_STATEMENT); }
|
case '$': settings_restore(SETTINGS_RESTORE_DEFAULTS); break;
|
||||||
switch (line[++char_counter]) {
|
#endif
|
||||||
case '$': settings_restore(SETTINGS_RESTORE_DEFAULTS); break;
|
#ifdef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS
|
||||||
case '#': settings_restore(SETTINGS_RESTORE_PARAMETERS); break;
|
case '#': settings_restore(SETTINGS_RESTORE_PARAMETERS); break;
|
||||||
case '*': settings_restore(SETTINGS_RESTORE_ALL); break;
|
#endif
|
||||||
|
#ifdef ENABLE_RESTORE_EEPROM_WIPE_ALL
|
||||||
|
case '*': settings_restore(SETTINGS_RESTORE_ALL); break;
|
||||||
|
#endif
|
||||||
default: return(STATUS_INVALID_STATEMENT);
|
default: return(STATUS_INVALID_STATEMENT);
|
||||||
}
|
}
|
||||||
report_feedback_message(MESSAGE_RESTORE_DEFAULTS);
|
report_feedback_message(MESSAGE_RESTORE_DEFAULTS);
|
||||||
@ -230,7 +234,7 @@ uint8_t system_execute_line(char *line)
|
|||||||
break;
|
break;
|
||||||
} else { // Store startup line [IDLE Only] Prevents motion during ALARM.
|
} else { // Store startup line [IDLE Only] Prevents motion during ALARM.
|
||||||
if (sys.state != STATE_IDLE) { return(STATUS_IDLE_ERROR); } // Store only when idle.
|
if (sys.state != STATE_IDLE) { return(STATUS_IDLE_ERROR); } // Store only when idle.
|
||||||
helper_var = true; // Set helper_var to flag storing method.
|
helper_var = true; // Set helper_var to flag storing method.
|
||||||
// No break. Continues into default: to read remaining command characters.
|
// No break. Continues into default: to read remaining command characters.
|
||||||
}
|
}
|
||||||
default : // Storing setting methods [IDLE/ALARM]
|
default : // Storing setting methods [IDLE/ALARM]
|
||||||
@ -245,7 +249,7 @@ uint8_t system_execute_line(char *line)
|
|||||||
// Execute gcode block to ensure block is valid.
|
// Execute gcode block to ensure block is valid.
|
||||||
helper_var = gc_execute_line(line); // Set helper_var to returned status code.
|
helper_var = gc_execute_line(line); // Set helper_var to returned status code.
|
||||||
if (helper_var) { return(helper_var); }
|
if (helper_var) { return(helper_var); }
|
||||||
else {
|
else {
|
||||||
helper_var = trunc(parameter); // Set helper_var to int value of parameter
|
helper_var = trunc(parameter); // Set helper_var to int value of parameter
|
||||||
settings_store_startup_line(helper_var,line);
|
settings_store_startup_line(helper_var,line);
|
||||||
}
|
}
|
||||||
@ -254,12 +258,22 @@ uint8_t system_execute_line(char *line)
|
|||||||
if((line[char_counter] != 0) || (parameter > 255)) { return(STATUS_INVALID_STATEMENT); }
|
if((line[char_counter] != 0) || (parameter > 255)) { return(STATUS_INVALID_STATEMENT); }
|
||||||
return(settings_store_global_setting((uint8_t)parameter, value));
|
return(settings_store_global_setting((uint8_t)parameter, value));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
return(STATUS_OK); // If '$' command makes it to here, then everything's ok.
|
return(STATUS_OK); // If '$' command makes it to here, then everything's ok.
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void system_flag_wco_change()
|
||||||
|
{
|
||||||
|
#ifdef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE
|
||||||
|
protocol_buffer_synchronize();
|
||||||
|
#endif
|
||||||
|
sys.report_wco_counter = REPORT_WCO_REFRESH_BUSY_COUNT;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
|
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
|
||||||
// NOTE: If motor steps and machine position are not in the same coordinate frame, this function
|
// NOTE: If motor steps and machine position are not in the same coordinate frame, this function
|
||||||
// serves as a central place to compute the transformation.
|
// serves as a central place to compute the transformation.
|
||||||
@ -267,10 +281,10 @@ float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx)
|
|||||||
{
|
{
|
||||||
float pos;
|
float pos;
|
||||||
#ifdef COREXY
|
#ifdef COREXY
|
||||||
if (idx==A_MOTOR) {
|
if (idx==X_AXIS) {
|
||||||
pos = 0.5*((steps[A_MOTOR] + steps[B_MOTOR])/settings.steps_per_mm[idx]);
|
pos = (float)system_convert_corexy_to_x_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||||
} else if (idx==B_MOTOR) {
|
} else if (idx==Y_AXIS) {
|
||||||
pos = 0.5*((steps[A_MOTOR] - steps[B_MOTOR])/settings.steps_per_mm[idx]);
|
pos = (float)system_convert_corexy_to_y_axis_steps(steps) / settings.steps_per_mm[idx];
|
||||||
} else {
|
} else {
|
||||||
pos = steps[idx]/settings.steps_per_mm[idx];
|
pos = steps[idx]/settings.steps_per_mm[idx];
|
||||||
}
|
}
|
||||||
@ -291,31 +305,94 @@ void system_convert_array_steps_to_mpos(float *position, int32_t *steps)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// CoreXY calculation only. Returns x or y-axis "steps" based on CoreXY motor steps.
|
||||||
|
#ifdef COREXY
|
||||||
|
int32_t system_convert_corexy_to_x_axis_steps(int32_t *steps)
|
||||||
|
{
|
||||||
|
return( (steps[A_MOTOR] + steps[B_MOTOR])/2 );
|
||||||
|
}
|
||||||
|
int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps)
|
||||||
|
{
|
||||||
|
return( (steps[A_MOTOR] - steps[B_MOTOR])/2 );
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
// Checks and reports if target array exceeds machine travel limits.
|
||||||
|
uint8_t system_check_travel_limits(float *target)
|
||||||
|
{
|
||||||
|
uint8_t idx;
|
||||||
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
|
#ifdef HOMING_FORCE_SET_ORIGIN
|
||||||
|
// When homing forced set origin is enabled, soft limits checks need to account for directionality.
|
||||||
|
// NOTE: max_travel is stored as negative
|
||||||
|
if (bit_istrue(settings.homing_dir_mask,bit(idx))) {
|
||||||
|
if (target[idx] < 0 || target[idx] > -settings.max_travel[idx]) { return(true); }
|
||||||
|
} else {
|
||||||
|
if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { return(true); }
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
// NOTE: max_travel is stored as negative
|
||||||
|
if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { return(true); }
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
return(false);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// Special handlers for setting and clearing Grbl's real-time execution flags.
|
// Special handlers for setting and clearing Grbl's real-time execution flags.
|
||||||
void system_set_exec_state_flag(uint8_t mask) {
|
void system_set_exec_state_flag(uint8_t mask) {
|
||||||
uint8_t sreg = SREG;
|
uint8_t sreg = SREG;
|
||||||
cli();
|
cli();
|
||||||
sys_rt_exec_state |= (mask);
|
sys_rt_exec_state |= (mask);
|
||||||
SREG = sreg;
|
SREG = sreg;
|
||||||
}
|
}
|
||||||
|
|
||||||
void system_clear_exec_state_flag(uint8_t mask) {
|
void system_clear_exec_state_flag(uint8_t mask) {
|
||||||
uint8_t sreg = SREG;
|
uint8_t sreg = SREG;
|
||||||
cli();
|
cli();
|
||||||
sys_rt_exec_state &= ~(mask);
|
sys_rt_exec_state &= ~(mask);
|
||||||
SREG = sreg;
|
SREG = sreg;
|
||||||
}
|
}
|
||||||
|
|
||||||
void system_set_exec_alarm_flag(uint8_t mask) {
|
void system_set_exec_alarm(uint8_t code) {
|
||||||
uint8_t sreg = SREG;
|
uint8_t sreg = SREG;
|
||||||
cli();
|
cli();
|
||||||
sys_rt_exec_alarm |= (mask);
|
sys_rt_exec_alarm = code;
|
||||||
SREG = sreg;
|
SREG = sreg;
|
||||||
}
|
}
|
||||||
|
|
||||||
void system_clear_exec_alarm_flag(uint8_t mask) {
|
void system_clear_exec_alarm_flag(uint8_t mask) {
|
||||||
uint8_t sreg = SREG;
|
uint8_t sreg = SREG;
|
||||||
cli();
|
cli();
|
||||||
sys_rt_exec_alarm &= ~(mask);
|
sys_rt_exec_alarm &= ~(mask);
|
||||||
SREG = sreg;
|
SREG = sreg;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void system_set_exec_motion_override_flag(uint8_t mask) {
|
||||||
|
uint8_t sreg = SREG;
|
||||||
|
cli();
|
||||||
|
sys_rt_exec_motion_override |= (mask);
|
||||||
|
SREG = sreg;
|
||||||
|
}
|
||||||
|
|
||||||
|
void system_set_exec_accessory_override_flag(uint8_t mask) {
|
||||||
|
uint8_t sreg = SREG;
|
||||||
|
cli();
|
||||||
|
sys_rt_exec_accessory_override |= (mask);
|
||||||
|
SREG = sreg;
|
||||||
|
}
|
||||||
|
|
||||||
|
void system_clear_exec_motion_overrides() {
|
||||||
|
uint8_t sreg = SREG;
|
||||||
|
cli();
|
||||||
|
sys_rt_exec_motion_override = 0;
|
||||||
|
SREG = sreg;
|
||||||
|
}
|
||||||
|
|
||||||
|
void system_clear_exec_accessory_overrides() {
|
||||||
|
uint8_t sreg = SREG;
|
||||||
|
cli();
|
||||||
|
sys_rt_exec_accessory_override = 0;
|
||||||
|
SREG = sreg;
|
||||||
|
}
|
||||||
|
135
grbl/system.h
135
grbl/system.h
@ -2,7 +2,7 @@
|
|||||||
system.h - Header for system level commands and real-time processes
|
system.h - Header for system level commands and real-time processes
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
|
|
||||||
Copyright (c) 2014-2015 Sungeun K. Jeon
|
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@ -23,10 +23,10 @@
|
|||||||
|
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
|
|
||||||
// Define system executor bit map. Used internally by realtime protocol as realtime command flags,
|
// Define system executor bit map. Used internally by realtime protocol as realtime command flags,
|
||||||
// which notifies the main program to execute the specified realtime command asynchronously.
|
// which notifies the main program to execute the specified realtime command asynchronously.
|
||||||
// NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default
|
// NOTE: The system executor uses an unsigned 8-bit volatile variable (8 flag limit.) The default
|
||||||
// flags are always false, so the realtime protocol only needs to check for a non-zero value to
|
// flags are always false, so the realtime protocol only needs to check for a non-zero value to
|
||||||
// know when there is a realtime command to execute.
|
// know when there is a realtime command to execute.
|
||||||
#define EXEC_STATUS_REPORT bit(0) // bitmask 00000001
|
#define EXEC_STATUS_REPORT bit(0) // bitmask 00000001
|
||||||
#define EXEC_CYCLE_START bit(1) // bitmask 00000010
|
#define EXEC_CYCLE_START bit(1) // bitmask 00000010
|
||||||
@ -35,17 +35,39 @@
|
|||||||
#define EXEC_RESET bit(4) // bitmask 00010000
|
#define EXEC_RESET bit(4) // bitmask 00010000
|
||||||
#define EXEC_SAFETY_DOOR bit(5) // bitmask 00100000
|
#define EXEC_SAFETY_DOOR bit(5) // bitmask 00100000
|
||||||
#define EXEC_MOTION_CANCEL bit(6) // bitmask 01000000
|
#define EXEC_MOTION_CANCEL bit(6) // bitmask 01000000
|
||||||
|
#define EXEC_SLEEP bit(7) // bitmask 10000000
|
||||||
|
|
||||||
// Alarm executor bit map.
|
// Alarm executor codes. Valid values (1-255). Zero is reserved.
|
||||||
// NOTE: EXEC_CRITICAL_EVENT is an optional flag that must be set with an alarm flag. When enabled,
|
#define EXEC_ALARM_HARD_LIMIT 1
|
||||||
// this halts Grbl into an infinite loop until the user aknowledges the problem and issues a soft-
|
#define EXEC_ALARM_SOFT_LIMIT 2
|
||||||
// reset command. For example, a hard limit event needs this type of halt and aknowledgement.
|
#define EXEC_ALARM_ABORT_CYCLE 3
|
||||||
#define EXEC_CRITICAL_EVENT bit(0) // bitmask 00000001 (SPECIAL FLAG. See NOTE:)
|
#define EXEC_ALARM_PROBE_FAIL_INITIAL 4
|
||||||
#define EXEC_ALARM_HARD_LIMIT bit(1) // bitmask 00000010
|
#define EXEC_ALARM_PROBE_FAIL_CONTACT 5
|
||||||
#define EXEC_ALARM_SOFT_LIMIT bit(2) // bitmask 00000100
|
#define EXEC_ALARM_HOMING_FAIL_RESET 6
|
||||||
#define EXEC_ALARM_ABORT_CYCLE bit(3) // bitmask 00001000
|
#define EXEC_ALARM_HOMING_FAIL_DOOR 7
|
||||||
#define EXEC_ALARM_PROBE_FAIL bit(4) // bitmask 00010000
|
#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8
|
||||||
#define EXEC_ALARM_HOMING_FAIL bit(5) // bitmask 00100000
|
#define EXEC_ALARM_HOMING_FAIL_APPROACH 9
|
||||||
|
|
||||||
|
// Override bit maps. Realtime bitflags to control feed, rapid, spindle, and coolant overrides.
|
||||||
|
// Spindle/coolant and feed/rapids are separated into two controlling flag variables.
|
||||||
|
#define EXEC_FEED_OVR_RESET bit(0)
|
||||||
|
#define EXEC_FEED_OVR_COARSE_PLUS bit(1)
|
||||||
|
#define EXEC_FEED_OVR_COARSE_MINUS bit(2)
|
||||||
|
#define EXEC_FEED_OVR_FINE_PLUS bit(3)
|
||||||
|
#define EXEC_FEED_OVR_FINE_MINUS bit(4)
|
||||||
|
#define EXEC_RAPID_OVR_RESET bit(5)
|
||||||
|
#define EXEC_RAPID_OVR_MEDIUM bit(6)
|
||||||
|
#define EXEC_RAPID_OVR_LOW bit(7)
|
||||||
|
// #define EXEC_RAPID_OVR_EXTRA_LOW bit(*) // *NOT SUPPORTED*
|
||||||
|
|
||||||
|
#define EXEC_SPINDLE_OVR_RESET bit(0)
|
||||||
|
#define EXEC_SPINDLE_OVR_COARSE_PLUS bit(1)
|
||||||
|
#define EXEC_SPINDLE_OVR_COARSE_MINUS bit(2)
|
||||||
|
#define EXEC_SPINDLE_OVR_FINE_PLUS bit(3)
|
||||||
|
#define EXEC_SPINDLE_OVR_FINE_MINUS bit(4)
|
||||||
|
#define EXEC_SPINDLE_OVR_STOP bit(5)
|
||||||
|
#define EXEC_COOLANT_FLOOD_OVR_TOGGLE bit(6)
|
||||||
|
#define EXEC_COOLANT_MIST_OVR_TOGGLE bit(7)
|
||||||
|
|
||||||
// Define system state bit map. The state variable primarily tracks the individual functions
|
// Define system state bit map. The state variable primarily tracks the individual functions
|
||||||
// of Grbl to manage each without overlapping. It is also used as a messaging flag for
|
// of Grbl to manage each without overlapping. It is also used as a messaging flag for
|
||||||
@ -56,8 +78,9 @@
|
|||||||
#define STATE_HOMING bit(2) // Performing homing cycle
|
#define STATE_HOMING bit(2) // Performing homing cycle
|
||||||
#define STATE_CYCLE bit(3) // Cycle is running or motions are being executed.
|
#define STATE_CYCLE bit(3) // Cycle is running or motions are being executed.
|
||||||
#define STATE_HOLD bit(4) // Active feed hold
|
#define STATE_HOLD bit(4) // Active feed hold
|
||||||
#define STATE_SAFETY_DOOR bit(5) // Safety door is ajar. Feed holds and de-energizes system.
|
#define STATE_JOG bit(5) // Jogging mode.
|
||||||
#define STATE_MOTION_CANCEL bit(6) // Motion cancel by feed hold and return to idle.
|
#define STATE_SAFETY_DOOR bit(6) // Safety door is ajar. Feed holds and de-energizes system.
|
||||||
|
#define STATE_SLEEP bit(7) // Sleep state.
|
||||||
|
|
||||||
// Define system suspend flags. Used in various ways to manage suspend states and procedures.
|
// Define system suspend flags. Used in various ways to manage suspend states and procedures.
|
||||||
#define SUSPEND_DISABLE 0 // Must be zero.
|
#define SUSPEND_DISABLE 0 // Must be zero.
|
||||||
@ -66,15 +89,16 @@
|
|||||||
#define SUSPEND_RETRACT_COMPLETE bit(2) // (Safety door only) Indicates retraction and de-energizing is complete.
|
#define SUSPEND_RETRACT_COMPLETE bit(2) // (Safety door only) Indicates retraction and de-energizing is complete.
|
||||||
#define SUSPEND_INITIATE_RESTORE bit(3) // (Safety door only) Flag to initiate resume procedures from a cycle start.
|
#define SUSPEND_INITIATE_RESTORE bit(3) // (Safety door only) Flag to initiate resume procedures from a cycle start.
|
||||||
#define SUSPEND_RESTORE_COMPLETE bit(4) // (Safety door only) Indicates ready to resume normal operation.
|
#define SUSPEND_RESTORE_COMPLETE bit(4) // (Safety door only) Indicates ready to resume normal operation.
|
||||||
#define SUSPEND_SAFETY_DOOR_AJAR bit(5) // Indicates suspend was initiated by a safety door state.
|
#define SUSPEND_SAFETY_DOOR_AJAR bit(5) // Tracks safety door state for resuming.
|
||||||
#define SUSPEND_MOTION_CANCEL bit(6) // Indicates a canceled resume motion. Currently used by probing routine.
|
#define SUSPEND_MOTION_CANCEL bit(6) // Indicates a canceled resume motion. Currently used by probing routine.
|
||||||
|
#define SUSPEND_JOG_CANCEL bit(7) // Indicates a jog cancel in process and to reset buffers when complete.
|
||||||
|
|
||||||
// Define step segment generator state flags.
|
// Define step segment generator state flags.
|
||||||
#define STEP_CONTROL_NORMAL_OP 0
|
#define STEP_CONTROL_NORMAL_OP 0
|
||||||
// #define STEP_CONTROL_RECOMPUTE_ACTIVE_BLOCK bit(0)
|
#define STEP_CONTROL_END_MOTION bit(0)
|
||||||
#define STEP_CONTROL_END_MOTION bit(1)
|
#define STEP_CONTROL_EXECUTE_HOLD bit(1)
|
||||||
#define STEP_CONTROL_EXECUTE_HOLD bit(2)
|
#define STEP_CONTROL_EXECUTE_SYS_MOTION bit(2)
|
||||||
#define STEP_CONTROL_EXECUTE_PARK bit(3)
|
#define STEP_CONTROL_UPDATE_SPINDLE_PWM bit(3)
|
||||||
|
|
||||||
// Define control pin index for Grbl internal use. Pin maps may change, but these values don't.
|
// Define control pin index for Grbl internal use. Pin maps may change, but these values don't.
|
||||||
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
|
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
|
||||||
@ -90,28 +114,49 @@
|
|||||||
#define CONTROL_PIN_INDEX_CYCLE_START bit(2)
|
#define CONTROL_PIN_INDEX_CYCLE_START bit(2)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// Define toggle override control states.
|
||||||
|
#define TOGGLE_OVR_STOP_ENABLED bit(0)
|
||||||
|
#define TOGGLE_OVR_STOP_INITIATE bit(1)
|
||||||
|
#define TOGGLE_OVR_STOP_RESTORE bit(2)
|
||||||
|
#define TOGGLE_OVR_STOP_RESTORE_CYCLE bit(3)
|
||||||
|
#define TOGGLE_OVR_FLOOD_COOLANT bit(4)
|
||||||
|
#define TOGGLE_OVR_MIST_COOLANT bit(5)
|
||||||
|
#define TOGGLE_OVR_STOP_ACTIVE_MASK (TOGGLE_OVR_STOP_ENABLED|TOGGLE_OVR_STOP_INITIATE|TOGGLE_OVR_STOP_RESTORE|TOGGLE_OVR_STOP_RESTORE_CYCLE)
|
||||||
|
// NOTE: Mask is used to determine if spindle stop is active or disabled.
|
||||||
|
|
||||||
|
|
||||||
// Define global system variables
|
// Define global system variables
|
||||||
typedef struct {
|
typedef struct {
|
||||||
uint8_t abort; // System abort flag. Forces exit back to main loop for reset.
|
uint8_t abort; // System abort flag. Forces exit back to main loop for reset.
|
||||||
uint8_t state; // Tracks the current state of Grbl.
|
uint8_t state; // Tracks the current system state of Grbl.
|
||||||
uint8_t suspend; // System suspend bitflag variable that manages holds, cancels, and safety door.
|
uint8_t suspend; // System suspend bitflag variable that manages holds, cancels, and safety door.
|
||||||
uint8_t soft_limit; // Tracks soft limit errors for the state machine (Boolean)
|
uint8_t soft_limit; // Tracks soft limit errors for the state machine. (boolean)
|
||||||
uint8_t step_control;
|
uint8_t step_control; // Governs the step segment generator depending on system state.
|
||||||
|
uint8_t probe_succeeded; // Tracks if last probing cycle was successful.
|
||||||
int32_t position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
|
uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR.
|
||||||
// NOTE: This may need to be a volatile variable, if problems arise.
|
uint8_t f_override; // Feed rate override value in percent
|
||||||
|
uint8_t r_override; // Rapids override value in percent
|
||||||
int32_t probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
|
uint8_t spindle_speed_ovr; // Spindle speed value in percent
|
||||||
uint8_t probe_succeeded; // Tracks if last probing cycle was successful.
|
uint8_t toggle_ovr_mask; // Tracks toggle override states
|
||||||
uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR.
|
uint8_t report_ovr_counter; // Tracks when to add override data to status reports.
|
||||||
|
uint8_t report_wco_counter; // Tracks when to add work coordinate offset data to status reports.
|
||||||
} system_t;
|
} system_t;
|
||||||
extern system_t sys;
|
extern system_t sys;
|
||||||
|
|
||||||
volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
|
// NOTE: These position variables may need to be declared as volatiles, if problems arise.
|
||||||
volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks.
|
int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
|
||||||
volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
|
int32_t sys_probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
|
||||||
|
|
||||||
|
volatile uint8_t sys_probe_state; // Probing state value. Used to coordinate the probing cycle with stepper ISR.
|
||||||
|
volatile uint8_t sys_rt_exec_state; // Global realtime executor bitflag variable for state management. See EXEC bitmasks.
|
||||||
|
volatile uint8_t sys_rt_exec_alarm; // Global realtime executor bitflag variable for setting various alarms.
|
||||||
|
volatile uint8_t sys_rt_exec_motion_override; // Global realtime executor bitflag variable for motion-based overrides.
|
||||||
|
volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bitflag variable for spindle/coolant overrides.
|
||||||
|
|
||||||
|
#ifdef DEBUG
|
||||||
|
#define EXEC_DEBUG_REPORT bit(0)
|
||||||
|
volatile uint8_t sys_rt_exec_debug;
|
||||||
|
#endif
|
||||||
|
|
||||||
// Initialize the serial protocol
|
// Initialize the serial protocol
|
||||||
void system_init();
|
void system_init();
|
||||||
@ -128,17 +173,33 @@ uint8_t system_execute_line(char *line);
|
|||||||
// Execute the startup script lines stored in EEPROM upon initialization
|
// Execute the startup script lines stored in EEPROM upon initialization
|
||||||
void system_execute_startup(char *line);
|
void system_execute_startup(char *line);
|
||||||
|
|
||||||
|
|
||||||
|
void system_flag_wco_change();
|
||||||
|
|
||||||
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
|
// Returns machine position of axis 'idx'. Must be sent a 'step' array.
|
||||||
float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx);
|
float system_convert_axis_steps_to_mpos(int32_t *steps, uint8_t idx);
|
||||||
|
|
||||||
// Updates a machine 'position' array based on the 'step' array sent.
|
// Updates a machine 'position' array based on the 'step' array sent.
|
||||||
void system_convert_array_steps_to_mpos(float *position, int32_t *steps);
|
void system_convert_array_steps_to_mpos(float *position, int32_t *steps);
|
||||||
|
|
||||||
|
// CoreXY calculation only. Returns x or y-axis "steps" based on CoreXY motor steps.
|
||||||
|
#ifdef COREXY
|
||||||
|
int32_t system_convert_corexy_to_x_axis_steps(int32_t *steps);
|
||||||
|
int32_t system_convert_corexy_to_y_axis_steps(int32_t *steps);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Checks and reports if target array exceeds machine travel limits.
|
||||||
|
uint8_t system_check_travel_limits(float *target);
|
||||||
|
|
||||||
// Special handlers for setting and clearing Grbl's real-time execution flags.
|
// Special handlers for setting and clearing Grbl's real-time execution flags.
|
||||||
void system_set_exec_state_flag(uint8_t mask);
|
void system_set_exec_state_flag(uint8_t mask);
|
||||||
void system_clear_exec_state_flag(uint8_t mask);
|
void system_clear_exec_state_flag(uint8_t mask);
|
||||||
void system_set_exec_alarm_flag(uint8_t mask);
|
void system_set_exec_alarm(uint8_t code);
|
||||||
void system_clear_exec_alarm_flag(uint8_t mask);
|
void system_clear_exec_alarm_flag(uint8_t mask);
|
||||||
|
void system_set_exec_motion_override_flag(uint8_t mask);
|
||||||
|
void system_set_exec_accessory_override_flag(uint8_t mask);
|
||||||
|
void system_clear_exec_motion_overrides();
|
||||||
|
void system_clear_exec_accessory_overrides();
|
||||||
|
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user