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.
This commit is contained in:
chamnit 2016-09-21 19:08:24 -06:00
parent 0746a5a1d7
commit 12f48a008a
48 changed files with 3998 additions and 2228 deletions

View File

@ -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

View File

@ -1,7 +1,7 @@
# Part of Grbl # Part of Grbl
# #
# Copyright (c) 2009-2011 Simen Svale Skogsrud # Copyright (c) 2009-2011 Simen Svale Skogsrud
# Copyright (c) 2012-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,7 @@ 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 = avr-gcc -Wall -Os -DF_CPU=$(CLOCK) -mmcu=$(DEVICE) -I. -ffunction-sections
OBJECTS = $(addprefix $(BUILDDIR)/,$(notdir $(SOURCE:.c=.o))) OBJECTS = $(addprefix $(BUILDDIR)/,$(notdir $(SOURCE:.c=.o)))

View File

@ -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.0'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 [_2011 - Current_]: Sungeun "Sonny" Jeon, Ph.D. (USA) aka @chamnit
* Lead Developer [_2009 - 2011_]: Simen Svale Skogsrud (Norway). aka The Originator/Creator/Pioneer/Father of Grbl. * This work is built on the wonderful Grbl v0.6 firmware in 2011 written by Simen Svale Skogsrud (Norway).
*** ***
@ -31,11 +31,9 @@ Grbl includes full acceleration management with look ahead. That means the contr
*** ***
##Update Summary for v1.0c ##Update Summary for v1.0
- **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.
- 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. - 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.
- 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.
@ -44,6 +42,8 @@ Grbl includes full acceleration management with look ahead. That means the contr
- **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. - **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.
- Single file configuration for custom firmware.
- A few bug fixes and lots of 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.

9
doc/csv/alarm_codes.csv Normal file
View File

@ -0,0 +1,9 @@
1,Hard limit,Hard limit has been triggered. Machine position is likely lost due to sudden stop. Re-homing is highly recommended.
2,Soft limit,G-code motion target exceeds machine travel. Machine position safely retained. Alarm may be unlocked.
3,Abort during cycle,Reset while in motion. Grbl cannot guarantee position. Lost steps are likely. Re-homing is highly recommended.
4,Probe fail,If 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,If the probe fails to contact the workpiece within the programmed travel for G38.2 and G38.4.
6,Homing fail,If the active homing cycle was reset.
7,Homing fail,If the safety door was opened during homing cycle.
8,Homing fail,Pull off travel failed to clear limit switch. Try increasing pull-off setting or check wiring.
9,Homing fail,Failed to find limit switch within travel. Defined as `1.5 * max_travel` on search and `5 * pulloff` on locate phases.
1 1 Hard limit Hard limit has been triggered. Machine position is likely lost due to sudden stop. Re-homing is highly recommended.
2 2 Soft limit G-code motion target exceeds machine travel. Machine position safely retained. Alarm may be unlocked.
3 3 Abort during cycle Reset while in motion. Grbl cannot guarantee position. Lost steps are likely. Re-homing is highly recommended.
4 4 Probe fail If 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 5 Probe fail If the probe fails to contact the workpiece within the programmed travel for G38.2 and G38.4.
6 6 Homing fail If the active homing cycle was reset.
7 7 Homing fail If the safety door was opened during homing cycle.
8 8 Homing fail Pull off travel failed to clear limit switch. Try increasing pull-off setting or check wiring.
9 9 Homing fail Failed to find limit switch within travel. Defined as `1.5 * max_travel` on search and `5 * pulloff` on locate phases.

34
doc/csv/error_codes.csv Normal file
View File

@ -0,0 +1,34 @@
1,Expected command letter,G-code words consist of a letter and a value. Letter was not found.
2,Bad number format,Numeric value format is not valid or missing an expected value.
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 is not enabled via settings.
6,Value < 3 usec,Minimum step pulse time must be greater than 3usec.
7,EEPROM read fail. Using defaults,EEPROM read failed. Reset and restored 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 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. Line was not processed and executed.
12,Step rate > 30kHz,Grbl '$' setting value exceeds the maximum step rate 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.
15,Travel exceeded,Jog target exceeds machine travel. Command ignored.
16,Invalid jog command,Jog command with 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 mode 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,Work coordinate system commanded not supported.
30,Invalid gcode ID:30,G53 only allowed during G0 and G1 motion modes.
31,Invalid gcode ID:31,Axis words found in block while no command uses them.
32,Invalid gcode ID:32,G2/3 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/3 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 assigned to wrong axis.
1 1 Expected command letter G-code words consist of a letter and a value. Letter was not found.
2 2 Bad number format Numeric value format is not valid or missing an expected value.
3 3 Invalid statement Grbl '$' system command was not recognized or supported.
4 4 Value < 0` Negative value received for an expected positive value.
5 5 Setting disabled Homing cycle is not enabled via settings.
6 6 Value < 3 usec Minimum step pulse time must be greater than 3usec.
7 7 EEPROM read fail. Using defaults EEPROM read failed. Reset and restored to default values.
8 8 Not idle Grbl '$' command cannot be used unless Grbl is IDLE. Ensures smooth operation during a job.
9 9 G-code lock G-code locked out during alarm or jog state.
10 10 Homing not enabled Soft limits cannot be enabled without homing also enabled.
11 11 Line overflow Max characters per line exceeded. Line was not processed and executed.
12 12 Step rate > 30kHz Grbl '$' setting value exceeds the maximum step rate supported.
13 13 Check Door Safety door detected as opened and door state initiated.
14 14 Line length exceeded Build info or startup line exceeded EEPROM line length limit.
15 15 Travel exceeded Jog target exceeds machine travel. Command ignored.
16 16 Invalid jog command Jog command with no '=' or contains prohibited g-code.
17 20 Unsupported command Unsupported or invalid g-code command found in block.
18 21 Modal group violation More than one g-code command from same modal group found in block.
19 22 Undefined feed rate Feed rate has not yet been set or is undefined.
20 23 Invalid gcode ID:23 G-code command in block requires an integer value.
21 24 Invalid gcode ID:24 More than one g-code command that requires axis words found in block.
22 25 Invalid gcode ID:25 Repeated g-code word found in block.
23 26 Invalid gcode ID:26 No axis words found in block for g-code command or mode which requires them.
24 27 Invalid gcode ID:27 Line number value is invalid.
25 28 Invalid gcode ID:28 G-code command is missing a required value word.
26 29 Invalid gcode ID:29 Work coordinate system commanded not supported.
27 30 Invalid gcode ID:30 G53 only allowed during G0 and G1 motion modes.
28 31 Invalid gcode ID:31 Axis words found in block while no command uses them.
29 32 Invalid gcode ID:32 G2/3 arcs require at least one in-plane axis word.
30 33 Invalid gcode ID:33 Motion command target is invalid.
31 34 Invalid gcode ID:34 Arc radius value is invalid.
32 35 Invalid gcode ID:35 G2/3 arcs require at least one in-plane offset word.
33 36 Invalid gcode ID:36 Unused value words found in block.
34 37 Invalid gcode ID:37 G43.1 dynamic tool length offset assigned to wrong axis.

124
doc/markdown/error_codes.md Normal file
View File

@ -0,0 +1,124 @@
## Meanings of Grbl messages and error/alarm codes
#### _'error:' Codes_
Format - `(v1.0)` `:` `(v0.9)` - `Description`
- `error:1` : `error: Expected command letter` - G-code words consist of a letter and a value. Letter was not found.
- `error:2` : `error: Bad number format` - Numeric value format is not valid or missing an expected value.
- `error:3` : `error: Invalid statement` - Grbl '$' system command was not recognized or supported
- `error:4` : `error: Value < 0` - Negative value received for an expected positive value.
- `error:5` : `error: Setting disabled` - Homing cycle is not enabled via settings.
- `error:6` : `error: Value < 3 usec` - Minimum step pulse time must be greater than 3usec
- `error:7` : `error: EEPROM read fail. Using defaults` - EEPROM read failed. Reset and restored to default values.
- `error:8` : `error: Not idle` - Grbl '$' command cannot be used unless Grbl is IDLE. Ensures smooth operation during a job.
- `error:9` : `error: G-code lock` - G-code locked out during alarm or jog state
- `error:10` : `error: Homing not enabled` - Soft limits cannot be enabled without homing also enabled.
- `error:11` : `error: Line overflow` - Max characters per line exceeded. Line was not processed and executed.
- `error:12` : `error: Step rate > 30kHz`* - Grbl '$' setting value exceeds the maximum step rate supported.
- `error:13` : `error: Check Door` - Safety door detected as opened and door state initiated.
- `error:14` : `error: Line length exceeded` - (Grbl-Mega Only) Build info or startup line exceeded EEPROM line length limit.
- `error:15` : `error: Travel exceeded` - Jog target exceeds machine travel. Command ignored.
- `error:16` : `error: Invalid jog command` - Jog command with no '=' or contains prohibited g-code.
- `error:20` : `error: Unsupported command` - Unsupported or invalid g-code command found in block.
- `error:21` : `error: Modal group violation` - More than one g-code command from same modal group found in block.
- `error:22` : `error: Undefined feed rate` - Feed rate has not yet been set or is undefined.
- `error:23` : `error: Invalid gcode ID:23` - G-code command in block requires an integer value.
- `error:24` : `error: Invalid gcode ID:24` - More than one g-code command that requires axis words found in block.
- `error:25` : `error: Invalid gcode ID:25` - Repeated g-code word found in block.
- `error:26` : `error: Invalid gcode ID:26` - No axis words found in block for g-code command or mode which requires them.
- `error:27` : `error: Invalid gcode ID:27` - Line number value is invalid
- `error:28` : `error: Invalid gcode ID:28` - G-code command is missing a required value word.
- `error:29` : `error: Invalid gcode ID:29` - Work coordinate system commanded not supported.
- `error:30` : `error: Invalid gcode ID:30` - G53 only allowed during G0 and G1 motion modes.
- `error:31` : `error: Invalid gcode ID:31` - Axis words found in block while no command uses them.
- `error:32` : `error: Invalid gcode ID:32` - G2/3 arcs require at least one in-plane axis word.
- `error:33` : `error: Invalid gcode ID:33` - Motion command target is invalid.
- `error:34` : `error: Invalid gcode ID:34` - Arc radius value is invalid.
- `error:35` : `error: Invalid gcode ID:35` - G2/3 arcs require at least one in-plane offset word.
- `error:36` : `error: Invalid gcode ID:36` - Unused value words found in block.
- `error:37` : `error: Invalid gcode ID:37` - G43.1 dynamic tool length offset assigned to wrong axis.
`*` indicates feedback enabled only by compile-time option.
-----
#### 'Alarm:' Codes
Format - `(v1.0)` `:` `(v0.9)` - `Description`
- `ALARM:1` : `ALARM: Hard limit` - Hard limit has been triggered. Machine position is likely lost due to sudden stop. Re-homing is highly recommended.
`
- `ALARM:2` : `ALARM: Soft limit` - G-code motion target exceeds machine travel. Machine position safely retained. Alarm may be unlocked.
- `ALARM:3` : `ALARM: Abort during cycle` - Reset while in motion. Grbl cannot guarantee position. Lost steps are likely. Re-homing is highly recommended.
- `ALARM:4` : `ALARM: Probe fail` - If 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.
- `ALARM:5` : `ALARM: Probe fail` - If the probe fails to contact the workpiece within the programmed travel for G38.2 and G38.4.
- `ALARM:6` : `ALARM: Homing fail` - If the active homing cycle was reset.
- `ALARM:7` : `ALARM: Homing fail` - If the safety door was opened during homing cycle.
- `ALARM:8` : `ALARM: Homing fail` - Pull off travel failed to clear limit switch. Try increasing pull-off setting or check wiring.
- `ALARM:9` : `ALARM: Homing fail` - Failed to find limit switch within travel. Defined as `1.5 * max_travel` on search and `5 * pulloff` on locate phases.
-----
#### Message Descriptions
Format - `Message` - `Description`
- `[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. Hard or soft limit errors will trigger this event.
- `[$H|$X to unlock]`- Alarm message at initialization. All g-code commands and some $ are blocked until unlocked via homing or $X.
- `[Caution: Unlocked]` - Alarm unlock $X acknowledgement.
- `[Enabled]` - Indicates Grbls check-mode is enabled.
- `[Disabled]` - Indicates Grbls check-mode is disabled. Grbl is automatically reset afterwards.
- `[Check Door]` - Safety door detected as open. This message appears either immediately upon a safety door ajar or if the safety is open when Grbl initializes after a power-up/reset.
- `[Check Limits]` - If Grbl detects a limit switch is triggered after power-up/reset and hard limits are enabled, this will appear as a courtesy message.
- `[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.
- `[Restoring defaults]` - Acknowledgement message when restoring EEPROM defaults via a `$RST=` command.

41
doc/markdown/jogging.md Normal file
View File

@ -0,0 +1,41 @@
## Grbl v1.0 Jogging
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 feed hold command. Grbl
will automatically flush Grbl's internal buffers of any queued jogging motions and return
to the 'Idle' state. No soft-reset required.
- 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.

View File

@ -0,0 +1,135 @@
## Grbl v1.0 Realtime commands
Realtime commands are single control characters that may be sent to Grbl to command and perform an action in real-time, regardless of what Grbl is doing at the time. These commands include a reset, feed hold, resume, status report query, and overrides (in v1.0).
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 carraige return after them.
- Is not considered a part of the streaming protocol.
- 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
The normal ASCII realtime command characters used in Grbl v0.9 have been retained in Grbl v1.0 and are described below for completeness.
- `0x18` (ctrl-x) : Soft-Reset
- Immediately halts and resets Grbl.
- 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.
- 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.0 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 readily 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.
- 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.
- 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.
- The command is otherwise ignored, especially while in motion. This prevents accidental disabling during a job that can either destroy the part/machine or 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 supercede 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.

279
doc/markdown/report.md Normal file
View File

@ -0,0 +1,279 @@
### _Grbl v1.0 Realtime Status Reports_ (Rev. 2)
--------
#### Summary of Changes from Grbl v0.9 Reports
- 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.0 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:0,0`. The first value is planner blocks in use and the second is RX bytes in use.
- 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.)
-------
#### Basic Characteristics
- Contains real-time data of Grbls 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`
- 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:0,0`. The first value is planner blocks in use and the second is RX bytes in use.
- This data field will not appear if:
- It is disabled by the `$` status report mask setting.
- **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.

View File

@ -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
@ -38,6 +38,7 @@
#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
@ -46,11 +47,40 @@
// 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 '!'
// #define CMD_SAFETY_DOOR '@' // Moved to extended ASCII.
// 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_DEBUG_REPORT 0x85 // 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
@ -113,14 +143,9 @@
// #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.
@ -128,7 +153,7 @@
// 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,
@ -147,7 +172,7 @@
// #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.
@ -173,12 +198,10 @@
// 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
@ -188,14 +211,83 @@
// 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 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
@ -325,10 +417,10 @@
// 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 16 // 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
@ -354,9 +446,12 @@
// 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.
// #define RX_BUFFER_SIZE 128 // (1-254) Uncomment to override defaults in serial.h
// #define TX_BUFFER_SIZE 90 // (1-254)
// Toggles XON/XOFF software flow control for serial communications. Not officially supported // Toggles XON/XOFF software flow control for serial communications. Not officially supported
// due to problems involving the Atmega8U2 USB-to-serial chips on current Arduinos. The firmware // due to problems involving the Atmega8U2 USB-to-serial chips on current Arduinos. The firmware
@ -397,6 +492,49 @@
// #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

View File

@ -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
@ -23,38 +23,44 @@
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);
#else
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT); COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
#endif
} else {
#ifdef INVERT_COOLANT_FLOOD_PIN
COOLANT_FLOOD_PORT |= (1 << COOLANT_FLOOD_BIT);
#else
COOLANT_FLOOD_PORT &= ~(1 << COOLANT_FLOOD_BIT);
#endif
}
#ifdef ENABLE_M7 #ifdef ENABLE_M7
} else if (mode == COOLANT_MIST_ENABLE) { 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); COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
#endif #endif
} else { } else {
coolant_stop(); #ifdef INVERT_COOLANT_MIST_PIN
COOLANT_MIST_PORT |= (1 << COOLANT_MIST_BIT);
#else
COOLANT_MIST_PORT &= ~(1 << COOLANT_MIST_BIT);
#endif
} }
#endif
} }
@ -62,5 +68,6 @@ 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);
} }

View File

@ -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
@ -23,7 +23,6 @@
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);

View File

@ -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
@ -93,16 +93,12 @@
#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 4 #define COOLANT_MIST_BIT 4 // Uno Analog Pin 3
#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).
@ -126,24 +122,26 @@
#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
#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
#define SPINDLE_TCCRB_INIT_MASK (1<<CS22) // 1/64 prescaler -> 0.98kHz
// NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings. // NOTE: On the 328p, these must be the same as the SPINDLE_ENABLE settings.
#define SPINDLE_PWM_DDR DDRB #define SPINDLE_PWM_DDR DDRB
#define SPINDLE_PWM_PORT PORTB #define SPINDLE_PWM_PORT PORTB
#define SPINDLE_PWM_BIT 3 // Uno Digital Pin 11 #define SPINDLE_PWM_BIT 3 // Uno Digital Pin 11
#endif // End of VARIABLE_SPINDLE
#endif #endif

View File

@ -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
@ -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 255 // All 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
@ -87,7 +89,7 @@
#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 255 // All 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
@ -130,7 +134,7 @@
#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 255 // All 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
@ -138,6 +142,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
@ -173,7 +179,7 @@
#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 255 // All 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
@ -181,6 +187,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
@ -223,6 +231,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 100.0 // mm/min #define DEFAULT_HOMING_FEED_RATE 100.0 // mm/min
@ -258,7 +268,7 @@
#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 255 // All 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
@ -266,6 +276,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 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
@ -301,7 +313,7 @@
#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 255 // All 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
@ -309,6 +321,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 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
@ -342,7 +356,7 @@
#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 255 // All 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
@ -350,6 +364,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
@ -379,7 +395,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 255 // All 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 255 // All 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

View 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); }
}

View 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.

View File

@ -2,7 +2,7 @@
gcode.c - rs274/ngc parser. gcode.c - 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
@ -24,7 +24,7 @@
// NOTE: Max line number is defined by the g-code standard to be 99999. It seems to be an // NOTE: Max line number is defined by the g-code standard to be 99999. It seems to be an
// arbitrary value, and some GUIs may require more. So we increased it based on a max safe // arbitrary value, and some GUIs may require more. So we increased it based on a max safe
// value when converting a float (7.2 digit precision)s to an integer. // value when converting a float (7.2 digit precision)s to an integer.
#define MAX_LINE_NUMBER 9999999 #define MAX_LINE_NUMBER 10000000
#define AXIS_COMMAND_NONE 0 #define AXIS_COMMAND_NONE 0
#define AXIS_COMMAND_NON_MODAL 1 #define AXIS_COMMAND_NON_MODAL 1
@ -53,7 +53,7 @@ void gc_init()
// limit pull-off routines. // limit pull-off routines.
void gc_sync_position() void gc_sync_position()
{ {
system_convert_array_steps_to_mpos(gc_state.position,sys.position); system_convert_array_steps_to_mpos(gc_state.position,sys_position);
} }
@ -82,6 +82,7 @@ uint8_t gc_execute_line(char *line)
memset(&gc_block, 0, sizeof(parser_block_t)); // Initialize the parser block struct. memset(&gc_block, 0, sizeof(parser_block_t)); // Initialize the parser block struct.
memcpy(&gc_block.modal,&gc_state.modal,sizeof(gc_modal_t)); // Copy current modes memcpy(&gc_block.modal,&gc_state.modal,sizeof(gc_modal_t)); // Copy current modes
uint8_t axis_command = AXIS_COMMAND_NONE; uint8_t axis_command = AXIS_COMMAND_NONE;
uint8_t axis_0, axis_1, axis_linear; uint8_t axis_0, axis_1, axis_linear;
uint8_t coord_select = 0; // Tracks G10 P coordinate selection for execution uint8_t coord_select = 0; // Tracks G10 P coordinate selection for execution
@ -96,6 +97,15 @@ uint8_t gc_execute_line(char *line)
uint16_t command_words = 0; // G and M command words. Also used for modal group violations. uint16_t command_words = 0; // G and M command words. Also used for modal group violations.
uint16_t value_words = 0; // Value words. uint16_t value_words = 0; // Value words.
// Determine if the line is a jogging motion or a normal g-code block.
uint8_t is_jog_motion = false;
if (line[0] == '$') { // NOTE: `$J=` already parsed when passed to this function.
// Set G1 and G94 enforced modes to ensure accurate error checks.
is_jog_motion = true;
gc_block.modal.motion = MOTION_MODE_LINEAR;
gc_block.modal.feed_rate = FEED_RATE_MODE_UNITS_PER_MIN;
}
/* ------------------------------------------------------------------------------------- /* -------------------------------------------------------------------------------------
STEP 2: Import all g-code words in the block line. A g-code word is a letter followed by STEP 2: Import all g-code words in the block line. A g-code word is a letter followed by
a number, which can either be a 'G'/'M' command or sets/assigns a command value. Also, a number, which can either be a 'G'/'M' command or sets/assigns a command value. Also,
@ -103,11 +113,13 @@ uint8_t gc_execute_line(char *line)
words, and for negative values set for the value words F, N, P, T, and S. */ words, and for negative values set for the value words F, N, P, T, and S. */
uint8_t word_bit; // Bit-value for assigning tracking variables uint8_t word_bit; // Bit-value for assigning tracking variables
uint8_t char_counter = 0; uint8_t char_counter;
char letter; char letter;
float value; float value;
uint8_t int_value = 0; uint8_t int_value = 0;
uint16_t mantissa = 0; uint16_t mantissa = 0;
if (is_jog_motion) { char_counter = 3; } // Start parsing after `$J=`
else { char_counter = 0; }
while (line[char_counter] != 0) { // Loop until no more g-code words in line. while (line[char_counter] != 0) { // Loop until no more g-code words in line.
@ -300,9 +312,10 @@ uint8_t gc_execute_line(char *line)
} }
break; break;
#ifdef ENABLE_M7 #ifdef ENABLE_M7
case 7: case 7: case 8: case 9:
#endif #else
case 8: case 9: case 8: case 9:
#endif
word_bit = MODAL_GROUP_M8; word_bit = MODAL_GROUP_M8;
switch(int_value) { switch(int_value) {
#ifdef ENABLE_M7 #ifdef ENABLE_M7
@ -442,7 +455,8 @@ uint8_t gc_execute_line(char *line)
if (bit_istrue(value_words,bit(WORD_F))) { if (bit_istrue(value_words,bit(WORD_F))) {
if (gc_block.modal.units == UNITS_MODE_INCHES) { gc_block.values.f *= MM_PER_INCH; } if (gc_block.modal.units == UNITS_MODE_INCHES) { gc_block.values.f *= MM_PER_INCH; }
} else { } else {
gc_block.values.f = gc_state.feed_rate; // Push last state feed rate // NOTE: Jogging mode does not pass modal feed rate and requires unique values for each command.
if (!is_jog_motion) { gc_block.values.f = gc_state.feed_rate; } // Push last state feed rate
} }
} // Else, switching to G94 from G93, so don't push last state feed rate. Its undefined or the passed F word value. } // Else, switching to G94 from G93, so don't push last state feed rate. Its undefined or the passed F word value.
} }
@ -837,29 +851,67 @@ uint8_t gc_execute_line(char *line)
if (value_words) { FAIL(STATUS_GCODE_UNUSED_WORDS); } // [Unused words] if (value_words) { FAIL(STATUS_GCODE_UNUSED_WORDS); } // [Unused words]
/* -------------------------------------------------------------------------------------
STEP 3.5ish : EXECUTE JOG!!
Intercept jog commands and complete error checking for valid jog commands and execute.
NOTE: G-code parser state is not updated, except the position to ensure sequential jog
targets are computed correctly. The final parser position after a jog is updated in
protocol_execute_realtime() when jogging completes or is canceled.
*/
if (is_jog_motion) {
// Only distance and unit modal commands and G53 absolute override command are allowed.
if (command_words & ~(bit(MODAL_GROUP_G3) | bit(MODAL_GROUP_G6 | bit(MODAL_GROUP_G0))) ) { FAIL(STATUS_INVALID_JOG_COMMAND) };
if (!(gc_block.non_modal_command == NON_MODAL_ABSOLUTE_OVERRIDE || gc_block.non_modal_command == NON_MODAL_NO_ACTION)) { FAIL(STATUS_INVALID_JOG_COMMAND); }
// NOTE: Feed rate word and axis word checks have already been performed in STEP 3.
uint8_t status = jog_execute(&gc_block);
if (status == STATUS_OK) { memcpy(gc_state.position, gc_block.values.xyz, sizeof(gc_block.values.xyz)); }
return(status);
}
/* ------------------------------------------------------------------------------------- /* -------------------------------------------------------------------------------------
STEP 4: EXECUTE!! STEP 4: EXECUTE!!
Assumes that all error-checking has been completed and no failure modes exist. We just Assumes that all error-checking has been completed and no failure modes exist. We just
need to update the state and execute the block according to the order-of-execution. need to update the state and execute the block according to the order-of-execution.
*/ */
// Initialize planner data struct for motion blocks.
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
// [0. Non-specific/common error-checks and miscellaneous setup]: // [0. Non-specific/common error-checks and miscellaneous setup]:
// NOTE: If no line number is present, the value is zero.
gc_state.line_number = gc_block.values.n; gc_state.line_number = gc_block.values.n;
#ifdef USE_LINE_NUMBERS
pl_data->line_number = gc_state.line_number; // Record data for planner use.
#endif
// [1. Comments feedback ]: NOT SUPPORTED // [1. Comments feedback ]: NOT SUPPORTED
// [2. Set feed rate mode ]: // [2. Set feed rate mode ]:
gc_state.modal.feed_rate = gc_block.modal.feed_rate; gc_state.modal.feed_rate = gc_block.modal.feed_rate;
pl_data->condition |= gc_state.modal.feed_rate; // Set condition flag for planner use.
// [3. Set feed rate ]: // [3. Set feed rate ]:
gc_state.feed_rate = gc_block.values.f; // Always copy this value. See feed rate error-checking. gc_state.feed_rate = gc_block.values.f; // Always copy this value. See feed rate error-checking.
pl_data->feed_rate = gc_state.feed_rate; // Record data for planner use.
// [4. Set spindle speed ]: // [4. Set spindle speed ]:
if (gc_state.spindle_speed != gc_block.values.s) { if (gc_state.spindle_speed != gc_block.values.s) {
#ifdef VARIABLE_SPINDLE
// Do not stop motion if in laser mode and a G1, G2, or G3 motion is being executed.
if ( !(bit_istrue(settings.flags,BITFLAG_LASER_MODE) && (axis_command == AXIS_COMMAND_MOTION_MODE) &&
((gc_block.modal.motion == MOTION_MODE_LINEAR ) || (gc_block.modal.motion == MOTION_MODE_CW_ARC) || (gc_block.modal.motion == MOTION_MODE_CCW_ARC)) ) ) {
// Update running spindle only if not in check mode and not already enabled. // Update running spindle only if not in check mode and not already enabled.
if (gc_state.modal.spindle != SPINDLE_DISABLE) { spindle_run(gc_state.modal.spindle, gc_block.values.s); } if (gc_state.modal.spindle != SPINDLE_DISABLE) { spindle_run(gc_state.modal.spindle, gc_block.values.s); }
}
#else
if (gc_state.modal.spindle != SPINDLE_DISABLE) { spindle_run(gc_state.modal.spindle, gc_block.values.s); }
#endif
gc_state.spindle_speed = gc_block.values.s; gc_state.spindle_speed = gc_block.values.s;
} }
pl_data->spindle_speed = gc_state.spindle_speed; // Record data for planner use.
// [5. Select tool ]: NOT SUPPORTED. Only tracks tool value. // [5. Select tool ]: NOT SUPPORTED. Only tracks tool value.
gc_state.tool = gc_block.values.t; gc_state.tool = gc_block.values.t;
@ -872,14 +924,19 @@ uint8_t gc_execute_line(char *line)
spindle_run(gc_block.modal.spindle, gc_state.spindle_speed); spindle_run(gc_block.modal.spindle, gc_state.spindle_speed);
gc_state.modal.spindle = gc_block.modal.spindle; gc_state.modal.spindle = gc_block.modal.spindle;
} }
pl_data->condition |= gc_state.modal.spindle; // Set condition flag for planner use.
// [8. Coolant control ]: // [8. Coolant control ]:
if (gc_state.modal.coolant != gc_block.modal.coolant) { if (gc_state.modal.coolant != gc_block.modal.coolant) {
// NOTE: Coolant M-codes are modal. Only one command per line is allowed. But, multiple states
// can exist at the same time, while coolant disable clears all states.
coolant_run(gc_block.modal.coolant); coolant_run(gc_block.modal.coolant);
gc_state.modal.coolant = gc_block.modal.coolant; if (gc_block.modal.coolant == COOLANT_DISABLE) { gc_state.modal.coolant = COOLANT_DISABLE; }
else { gc_state.modal.coolant |= gc_block.modal.coolant; }
} }
pl_data->condition |= gc_state.modal.coolant; // Set condition flag for planner use.
// [9. Enable/disable feed rate or spindle overrides ]: NOT SUPPORTED // [9. Enable/disable feed rate or spindle overrides ]: NOT SUPPORTED. Always enabled.
// [10. Dwell ]: // [10. Dwell ]:
if (gc_block.non_modal_command == NON_MODAL_DWELL) { mc_dwell(gc_block.values.p); } if (gc_block.non_modal_command == NON_MODAL_DWELL) { mc_dwell(gc_block.values.p); }
@ -899,10 +956,12 @@ uint8_t gc_execute_line(char *line)
// axis of the block XYZ value array. // axis of the block XYZ value array.
if (axis_command == AXIS_COMMAND_TOOL_LENGTH_OFFSET ) { // Indicates a change. if (axis_command == AXIS_COMMAND_TOOL_LENGTH_OFFSET ) { // Indicates a change.
gc_state.modal.tool_length = gc_block.modal.tool_length; gc_state.modal.tool_length = gc_block.modal.tool_length;
if (gc_state.modal.tool_length == TOOL_LENGTH_OFFSET_ENABLE_DYNAMIC) { // G43.1 if (gc_state.modal.tool_length == TOOL_LENGTH_OFFSET_CANCEL) { // G49
gc_block.values.xyz[TOOL_LENGTH_OFFSET_AXIS] = 0.0;
} // else G43.1
if ( gc_state.tool_length_offset != gc_block.values.xyz[TOOL_LENGTH_OFFSET_AXIS] ) {
gc_state.tool_length_offset = gc_block.values.xyz[TOOL_LENGTH_OFFSET_AXIS]; gc_state.tool_length_offset = gc_block.values.xyz[TOOL_LENGTH_OFFSET_AXIS];
} else { // G49 system_flag_wco_change();
gc_state.tool_length_offset = 0.0;
} }
} }
@ -910,6 +969,7 @@ uint8_t gc_execute_line(char *line)
if (gc_state.modal.coord_select != gc_block.modal.coord_select) { if (gc_state.modal.coord_select != gc_block.modal.coord_select) {
gc_state.modal.coord_select = gc_block.modal.coord_select; gc_state.modal.coord_select = gc_block.modal.coord_select;
memcpy(gc_state.coord_system,coordinate_data,sizeof(coordinate_data)); memcpy(gc_state.coord_system,coordinate_data,sizeof(coordinate_data));
system_flag_wco_change();
} }
// [16. Set path control mode ]: G61.1/G64 NOT SUPPORTED // [16. Set path control mode ]: G61.1/G64 NOT SUPPORTED
@ -925,23 +985,17 @@ uint8_t gc_execute_line(char *line)
case NON_MODAL_SET_COORDINATE_DATA: case NON_MODAL_SET_COORDINATE_DATA:
settings_write_coord_data(coord_select,parameter_data); settings_write_coord_data(coord_select,parameter_data);
// Update system coordinate system if currently active. // Update system coordinate system if currently active.
if (gc_state.modal.coord_select == coord_select) { memcpy(gc_state.coord_system,parameter_data,sizeof(parameter_data)); } if (gc_state.modal.coord_select == coord_select) {
memcpy(gc_state.coord_system,parameter_data,sizeof(parameter_data));
system_flag_wco_change();
}
break; break;
case NON_MODAL_GO_HOME_0: case NON_MODAL_GO_HOME_1: case NON_MODAL_GO_HOME_0: case NON_MODAL_GO_HOME_1:
// Move to intermediate position before going home. Obeys current coordinate system and offsets // Move to intermediate position before going home. Obeys current coordinate system and offsets
// and absolute and incremental modes. // and absolute and incremental modes.
if (axis_command) { pl_data->condition |= PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
#ifdef USE_LINE_NUMBERS if (axis_command) { mc_line(gc_block.values.xyz, pl_data); }
mc_line(gc_block.values.xyz, -1.0, false, gc_state.line_number); mc_line(parameter_data, pl_data);
#else
mc_line(gc_block.values.xyz, -1.0, false);
#endif
}
#ifdef USE_LINE_NUMBERS
mc_line(parameter_data, -1.0, false, gc_state.line_number);
#else
mc_line(parameter_data, -1.0, false);
#endif
memcpy(gc_state.position, parameter_data, sizeof(parameter_data)); memcpy(gc_state.position, parameter_data, sizeof(parameter_data));
break; break;
case NON_MODAL_SET_HOME_0: case NON_MODAL_SET_HOME_0:
@ -952,9 +1006,11 @@ uint8_t gc_execute_line(char *line)
break; break;
case NON_MODAL_SET_COORDINATE_OFFSET: case NON_MODAL_SET_COORDINATE_OFFSET:
memcpy(gc_state.coord_offset,gc_block.values.xyz,sizeof(gc_block.values.xyz)); memcpy(gc_state.coord_offset,gc_block.values.xyz,sizeof(gc_block.values.xyz));
system_flag_wco_change();
break; break;
case NON_MODAL_RESET_COORDINATE_OFFSET: case NON_MODAL_RESET_COORDINATE_OFFSET:
clear_vector(gc_state.coord_offset); // Disable G92 offsets by zeroing offset vector. clear_vector(gc_state.coord_offset); // Disable G92 offsets by zeroing offset vector.
system_flag_wco_change();
break; break;
} }
@ -967,66 +1023,33 @@ uint8_t gc_execute_line(char *line)
if (axis_command == AXIS_COMMAND_MOTION_MODE) { if (axis_command == AXIS_COMMAND_MOTION_MODE) {
switch (gc_state.modal.motion) { switch (gc_state.modal.motion) {
case MOTION_MODE_SEEK: case MOTION_MODE_SEEK:
#ifdef USE_LINE_NUMBERS pl_data->condition |= PL_COND_FLAG_RAPID_MOTION; // Set rapid motion condition flag.
mc_line(gc_block.values.xyz, -1.0, false, gc_state.line_number); mc_line(gc_block.values.xyz, pl_data);
#else
mc_line(gc_block.values.xyz, -1.0, false);
#endif
break; break;
case MOTION_MODE_LINEAR: case MOTION_MODE_LINEAR:
#ifdef USE_LINE_NUMBERS mc_line(gc_block.values.xyz, pl_data);
mc_line(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, gc_state.line_number);
#else
mc_line(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate);
#endif
break; break;
case MOTION_MODE_CW_ARC: case MOTION_MODE_CW_ARC:
#ifdef USE_LINE_NUMBERS mc_arc(gc_block.values.xyz, pl_data, gc_state.position, gc_block.values.ijk, gc_block.values.r,
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r, axis_0, axis_1, axis_linear, true);
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, true, gc_state.line_number);
#else
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r,
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, true);
#endif
break; break;
case MOTION_MODE_CCW_ARC: case MOTION_MODE_CCW_ARC:
#ifdef USE_LINE_NUMBERS mc_arc(gc_block.values.xyz, pl_data, gc_state.position, gc_block.values.ijk, gc_block.values.r,
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r, axis_0, axis_1, axis_linear, false);
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, false, gc_state.line_number);
#else
mc_arc(gc_state.position, gc_block.values.xyz, gc_block.values.ijk, gc_block.values.r,
gc_state.feed_rate, gc_state.modal.feed_rate, axis_0, axis_1, axis_linear, false);
#endif
break; break;
case MOTION_MODE_PROBE_TOWARD: case MOTION_MODE_PROBE_TOWARD:
// NOTE: gc_block.values.xyz is returned from mc_probe_cycle with the updated position value. So // NOTE: gc_block.values.xyz is returned from mc_probe_cycle with the updated position value. So
// upon a successful probing cycle, the machine position and the returned value should be the same. // upon a successful probing cycle, the machine position and the returned value should be the same.
#ifdef USE_LINE_NUMBERS mc_probe_cycle(gc_block.values.xyz, pl_data, false, false);
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, false, gc_state.line_number);
#else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, false);
#endif
break; break;
case MOTION_MODE_PROBE_TOWARD_NO_ERROR: case MOTION_MODE_PROBE_TOWARD_NO_ERROR:
#ifdef USE_LINE_NUMBERS mc_probe_cycle(gc_block.values.xyz, pl_data, false, true);
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, true, gc_state.line_number);
#else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, false, true);
#endif
break; break;
case MOTION_MODE_PROBE_AWAY: case MOTION_MODE_PROBE_AWAY:
#ifdef USE_LINE_NUMBERS mc_probe_cycle(gc_block.values.xyz, pl_data, true, false);
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, false, gc_state.line_number);
#else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, false);
#endif
break; break;
case MOTION_MODE_PROBE_AWAY_NO_ERROR: case MOTION_MODE_PROBE_AWAY_NO_ERROR:
#ifdef USE_LINE_NUMBERS mc_probe_cycle(gc_block.values.xyz, pl_data, true, true);
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, true, gc_state.line_number);
#else
mc_probe_cycle(gc_block.values.xyz, gc_state.feed_rate, gc_state.modal.feed_rate, true, true);
#endif
} }
// As far as the parser is concerned, the position is now == target. In reality the // As far as the parser is concerned, the position is now == target. In reality the
@ -1062,20 +1085,27 @@ uint8_t gc_execute_line(char *line)
gc_state.modal.coolant = COOLANT_DISABLE; gc_state.modal.coolant = COOLANT_DISABLE;
// gc_state.modal.override = OVERRIDE_DISABLE; // Not supported. // gc_state.modal.override = OVERRIDE_DISABLE; // Not supported.
#ifdef RESTORE_OVERRIDES_AFTER_PROGRAM_END
sys.f_override = DEFAULT_FEED_OVERRIDE;
sys.r_override = DEFAULT_RAPID_OVERRIDE;
sys.spindle_speed_ovr = DEFAULT_SPINDLE_SPEED_OVERRIDE;
#endif
// Execute coordinate change and spindle/coolant stop. // Execute coordinate change and spindle/coolant stop.
if (sys.state != STATE_CHECK_MODE) { if (sys.state != STATE_CHECK_MODE) {
if (!(settings_read_coord_data(gc_state.modal.coord_select,coordinate_data))) { FAIL(STATUS_SETTING_READ_FAIL); } if (!(settings_read_coord_data(gc_state.modal.coord_select,coordinate_data))) { FAIL(STATUS_SETTING_READ_FAIL); }
memcpy(gc_state.coord_system,coordinate_data,sizeof(coordinate_data)); memcpy(gc_state.coord_system,coordinate_data,sizeof(coordinate_data));
system_flag_wco_change(); // Set to refresh immediately just in case something altered.
spindle_stop(); spindle_stop();
coolant_stop(); coolant_set_state(COOLANT_DISABLE);
} }
report_feedback_message(MESSAGE_PROGRAM_END); report_feedback_message(MESSAGE_PROGRAM_END);
} }
gc_state.modal.program_flow = PROGRAM_FLOW_RUNNING; // Reset program flow. gc_state.modal.program_flow = PROGRAM_FLOW_RUNNING; // Reset program flow.
} }
// TODO: % to denote start of program. // TODO: % to denote start of program.
return(STATUS_OK); return(STATUS_OK);
} }
@ -1099,7 +1129,7 @@ uint8_t gc_execute_line(char *line)
group 6 = {M6} (Tool change) group 6 = {M6} (Tool change)
group 7 = {G41, G42} cutter radius compensation (G40 is supported) group 7 = {G41, G42} cutter radius compensation (G40 is supported)
group 8 = {G43} tool length offset (G43.1/G49 are supported) group 8 = {G43} tool length offset (G43.1/G49 are supported)
group 8 = {*M7} enable mist coolant (* Compile-option) group 8 = {M7*} enable mist coolant (* Compile-option)
group 9 = {M48, M49} enable/disable feed and speed override switches group 9 = {M48, M49} enable/disable feed and speed override switches
group 10 = {G98, G99} return mode canned cycles group 10 = {G98, G99} return mode canned cycles
group 13 = {G61.1, G64} path control mode (G61 is supported) group 13 = {G61.1, G64} path control mode (G61 is supported)

View File

@ -2,7 +2,7 @@
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
@ -94,7 +94,7 @@
// 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)
@ -189,16 +189,13 @@ typedef struct {
} 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();

View File

@ -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.0e"
#define GRBL_VERSION_BUILD "20160330" #define GRBL_VERSION_BUILD "20160921"
// Define standard libraries used by Grbl. // Define standard libraries used by Grbl.
#include <avr/io.h> #include <avr/io.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
View 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
View 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

View File

@ -2,7 +2,7 @@
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
@ -109,11 +109,11 @@ uint8_t limits_get_state()
// Check limit pin state. // 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 #else
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
#endif #endif
} }
} }
@ -129,7 +129,7 @@ uint8_t limits_get_state()
// Check limit pin state. // 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
} }
} }
} }
@ -148,7 +148,16 @@ 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];
@ -175,7 +184,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,7 +193,20 @@ 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))) {
@ -202,15 +224,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.
#endif
sys.step_control = STEP_CONTROL_EXECUTE_SYS_MOTION; // Set to execute homing motion and clear existing flags.
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 +237,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 +254,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;
@ -246,8 +277,6 @@ void limits_go_home(uint8_t cycle_mask)
} 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).
@ -270,9 +299,6 @@ void limits_go_home(uint8_t cycle_mask)
// 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++) {
@ -290,49 +316,33 @@ void limits_go_home(uint8_t cycle_mask)
#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;
#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]) { sys.soft_limit = true; }
} else {
if (target[idx] > 0 || target[idx] < settings.max_travel[idx]) { sys.soft_limit = true; }
}
#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 // 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 // workspace volume so just come to a controlled stop so position is not lost. When complete
// enter alarm mode. // enter alarm mode.
@ -343,11 +353,9 @@ void limits_soft_check(float *target)
if (sys.abort) { return; } if (sys.abort) { return; }
} while ( sys.state != STATE_IDLE ); } while ( sys.state != STATE_IDLE );
} }
mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown. mc_reset(); // Issue system reset and ensure spindle and coolant are shutdown.
system_set_exec_alarm_flag((EXEC_ALARM_SOFT_LIMIT|EXEC_CRITICAL_EVENT)); // Indicate soft limit critical event 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 protocol_execute_realtime(); // Execute to enter critical event loop and system abort
return; return;
} }
}
} }

View File

@ -2,7 +2,7 @@
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

View File

@ -2,7 +2,7 @@
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
@ -76,11 +76,23 @@ 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();

View File

@ -2,9 +2,8 @@
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
@ -30,15 +29,14 @@
// 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; }
@ -68,11 +66,7 @@
// 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
} }
@ -83,13 +77,8 @@
// 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];
@ -117,7 +106,7 @@
// 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;
@ -181,22 +170,14 @@
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
} }
@ -220,7 +201,7 @@ void mc_homing_cycle()
#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
@ -245,8 +226,9 @@ void mc_homing_cycle()
// 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,13 +237,7 @@ 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 void 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; }
@ -276,17 +252,13 @@ void mc_homing_cycle()
// 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();
} }
if (sys.abort) { return; } // Return if system reset has been issued. 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;
@ -302,8 +274,8 @@ void mc_homing_cycle()
// 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.
} }
@ -312,13 +284,13 @@ void mc_homing_cycle()
if (sys.abort) { return; } // Check for system abort if (sys.abort) { return; } // Check for system abort
// Reset the stepper and planner buffers to remove the remainder of the probe motion. // Reset the stepper and planner buffers to remove the remainder of the probe motion.
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. // 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. // 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); 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.
@ -329,17 +301,14 @@ void mc_homing_cycle()
// 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();
@ -347,10 +316,10 @@ void mc_parking_motion(float *parking_target, float feed_rate)
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();
} }
@ -370,16 +339,16 @@ void mc_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.
} }
} }

View File

@ -2,7 +2,7 @@
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
@ -23,29 +23,21 @@
#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 void 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();

View File

@ -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
@ -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.
@ -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);
}

View File

@ -2,7 +2,7 @@
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
@ -25,6 +25,8 @@
#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.
@ -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))
@ -78,4 +80,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

View File

@ -2,7 +2,7 @@
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
@ -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,7 +35,7 @@ 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;
@ -201,6 +199,12 @@ static void planner_recalculate()
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)
@ -219,12 +223,14 @@ 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]);
} }
// Returns address of first planner block, if available. Called by various main program functions.
plan_block_t *plan_get_current_block() 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
@ -232,11 +238,11 @@ plan_block_t *plan_get_current_block()
} }
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,6 +254,53 @@ 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.
@ -258,35 +311,30 @@ uint8_t plan_check_full_buffer()
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
@ -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,110 +367,91 @@ 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. // Set direction bits. Bit enabled always means direction is negative.
if (delta_mm < 0 ) { block->direction_bits |= get_direction_pin_mask(idx); } if (delta_mm < 0.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. // Bail if this is a zero-length block. Highly unlikely to occur.
if (block->step_event_count == 0) { return(PLAN_EMPTY_BLOCK); } 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 // 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. // 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.
NOTE: If the junction deviation value is finite, Grbl executes the motions in an exact path float junction_unit_vec[N_AXIS];
mode (G61). If the junction deviation value is zero, Grbl will execute the motion in an exact float junction_cos_theta = 0.0;
stop mode (G61.1) manner. In the future, if continuous mode (G64) is desired, the math here for (idx=0; idx<N_AXIS; idx++) {
is exactly the same. Instead of motioning all the way to junction point, the machine will junction_cos_theta -= pl.previous_unit_vec[idx]*unit_vec[idx];
just follow the arc circle defined here. The Arduino doesn't have the CPU cycles to perform junction_unit_vec[idx] = unit_vec[idx]-pl.previous_unit_vec[idx];
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) {
// Junction is a straight line or 180 degrees. Junction speed is infinite.
block->max_junction_speed_sqr = SOME_LARGE_VALUE;
} else {
convert_delta_vector_to_unit_vector(junction_unit_vec);
float junction_acceleration = limit_value_by_axis_maximum(settings.acceleration, junction_unit_vec);
float sin_theta_d2 = sqrt(0.5*(1.0-junction_cos_theta)); // Trig half angle identity. Always positive. float sin_theta_d2 = sqrt(0.5*(1.0-junction_cos_theta)); // Trig half angle identity. Always positive.
// TODO: Technically, the acceleration used in calculation needs to be limited by the minimum of the
// two junctions. However, this shouldn't be a significant problem except in extreme circumstances.
block->max_junction_speed_sqr = max( MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED, block->max_junction_speed_sqr = max( MINIMUM_JUNCTION_SPEED*MINIMUM_JUNCTION_SPEED,
(block->acceleration * settings.junction_deviation * sin_theta_d2)/(1.0-sin_theta_d2) ); (junction_acceleration * settings.junction_deviation * sin_theta_d2)/(1.0-sin_theta_d2) );
}
} }
} }
// Store block nominal speed // Block system motion from updating this data to ensure next g-code motion is computed correctly.
block->nominal_speed_sqr = feed_rate*feed_rate; // (mm/min). Always > 0 if (!(block->condition & PL_COND_FLAG_SYSTEM_MOTION)) {
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;
// Compute the junction maximum entry based on the minimum of the junction speed and neighboring nominal speeds. // Update previous path unit_vector and planner position.
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.
if (!is_parking_motion) {
// Update previous path unit_vector and nominal speed (squared)
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.
@ -444,15 +473,15 @@ void plan_sync_position()
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
} }
} }

View File

@ -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 16
#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;
// 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 // Initialize and reset the motion plan subsystem
void plan_reset(); 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 // 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();
@ -101,4 +137,7 @@ 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

View File

@ -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
@ -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,23 +94,6 @@ 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) {
@ -145,7 +146,7 @@ void printFloat(float n, uint8_t decimal_places)
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.

View File

@ -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,15 +31,12 @@ 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.

View File

@ -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
@ -34,7 +34,7 @@ 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.
} }
@ -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);
} }
}
} }

View File

@ -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

View File

@ -2,7 +2,7 @@
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
@ -37,28 +37,32 @@ static void protocol_exec_rt_suspend();
*/ */
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) { if (sys.state == STATE_ALARM) {
report_feedback_message(MESSAGE_ALARM_LOCK); report_feedback_message(MESSAGE_ALARM_LOCK);
} 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;
@ -68,14 +72,6 @@ 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
@ -97,9 +93,9 @@ void protocol_main_loop()
} 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));
@ -179,18 +175,18 @@ 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
// intended as a beginners feature to help new users to understand g-code. It can be disabled
// as a beginner tool, but (1.) still operates. If disabled, the operation of cycle start is
// manually issuing a cycle start command whenever the user is ready and there is a valid motion
// command in the planner queue.
// NOTE: This function is called from the main loop, buffer sync, and mc_line() only and executes // 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 // 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 // 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
@ -223,19 +219,9 @@ 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_HARD_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 {
@ -243,14 +229,7 @@ void protocol_exec_rt_system()
// 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
@ -271,20 +250,21 @@ void protocol_exec_rt_system()
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, // NOTE: Once hold is initiated, the system immediately enters a suspend state to block all
// operational scenarios. Once hold is initiated, the system enters a suspend state to block // main program processes until either reset or resumed. This ensures a hold completes safely.
// all main program processes until either reset or resumed.
if (rt_exec & (EXEC_MOTION_CANCEL | EXEC_FEED_HOLD | EXEC_SAFETY_DOOR)) { 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. // 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 ((sys.state == STATE_IDLE) ||
(sys.state & (STATE_CYCLE | STATE_HOMING | STATE_HOLD | STATE_SAFETY_DOOR | STATE_JOG))) {
// If in CYCLE state, all hold states immediately initiate a motion HOLD. // If in CYCLE or JOG states, immediately initiate a motion HOLD.
if (sys.state == STATE_CYCLE) { 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. 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. sys.step_control = STEP_CONTROL_EXECUTE_HOLD; // Initiate suspend state with active flag.
if (sys.state == STATE_JOG) { sys.suspend |= SUSPEND_JOG_CANCEL; } // Jog cancelled upon any hold event.
}
} }
// 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) {
@ -297,8 +277,7 @@ void protocol_exec_rt_system()
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. If so, only flag that motion cancel is complete.
if (sys.state == STATE_CYCLE) { sys.state = STATE_MOTION_CANCEL; } // NOTE: State is still STATE_CYCLE.
// NOTE: Ensures the motion cancel is handled correctly if it is active during a HOLD or DOOR state.
sys.suspend |= SUSPEND_MOTION_CANCEL; // Indicate motion cancel when resuming. sys.suspend |= SUSPEND_MOTION_CANCEL; // Indicate motion cancel when resuming.
} }
@ -306,7 +285,7 @@ void protocol_exec_rt_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 state from prematurely changing back to HOLD, which should only
// occur if the safety door switch closes. // occur if the safety door switch closes.
if (sys.state != STATE_SAFETY_DOOR) { sys.state = STATE_HOLD; } if (!(sys.state & (STATE_SAFETY_DOOR | STATE_JOG))) { 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.
@ -314,16 +293,17 @@ void protocol_exec_rt_system()
// 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.
if (!(sys.suspend & SUSPEND_JOG_CANCEL)) {
// Check if the safety re-opened during a restore parking motion only. Ignore if // Check if the safety re-opened during a restore parking motion only. Ignore if
// already retracting or parked. // already retracting or parked.
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) { if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
if (sys.suspend & SUSPEND_INITIATE_RESTORE) { // Actively restoring if (sys.suspend & SUSPEND_INITIATE_RESTORE) { // Actively restoring
#ifdef PARKING_ENABLE #ifdef PARKING_ENABLE
// Set hold and reset appropriate control flags to restart parking sequence. // Set hold and reset appropriate control flags to restart parking sequence.
if (sys.step_control & STEP_CONTROL_EXECUTE_PARK) { if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) {
st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration. st_update_plan_block_parameters(); // Notify stepper module to recompute for hold deceleration.
sys.step_control = (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_PARK); sys.step_control = (STEP_CONTROL_EXECUTE_HOLD | STEP_CONTROL_EXECUTE_SYS_MOTION);
sys.suspend &= ~(SUSPEND_HOLD_COMPLETE); sys.suspend &= ~(SUSPEND_HOLD_COMPLETE);
} // else NO_MOTION is active. } // else NO_MOTION is active.
#endif #endif
@ -331,11 +311,11 @@ void protocol_exec_rt_system()
sys.suspend |= SUSPEND_RESTART_RETRACT; sys.suspend |= SUSPEND_RESTART_RETRACT;
} }
} }
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;
} }
} }
@ -348,24 +328,24 @@ void protocol_exec_rt_system()
// 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))) {
// Cycle start only when IDLE or when a hold is complete and ready to resume. // Resume door state when parking motion has retracted and door has been closed.
// NOTE: SAFETY_DOOR is implicitly blocked. It reverts to HOLD when the door is closed. if ((sys.state == STATE_SAFETY_DOOR) && !(sys.suspend & SUSPEND_SAFETY_DOOR_AJAR)) {
if ((sys.state == STATE_IDLE) || ((sys.state & (STATE_HOLD | STATE_MOTION_CANCEL)) && (sys.suspend & SUSPEND_HOLD_COMPLETE))) { if (sys.suspend & SUSPEND_RESTORE_COMPLETE) {
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) { sys.state = STATE_IDLE; // Set to IDLE to immediately resume the cycle.
if (sys.suspend & SUSPEND_RETRACT_COMPLETE) { } else if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
if bit_isfalse(sys.suspend,SUSPEND_RESTORE_COMPLETE) {
// Flag to re-energize powered components and restore original position, if disabled by SAFETY_DOOR. // 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 // 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 // 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, // 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. // they are complete, it will call CYCLE_START automatically to resume and exit the suspend.
sys.suspend |= SUSPEND_INITIATE_RESTORE; sys.suspend |= SUSPEND_INITIATE_RESTORE;
}
}
// Cycle start only when IDLE or when a hold is complete and ready to resume.
if ((sys.state == STATE_IDLE) || ((sys.state & STATE_HOLD) && (sys.suspend & SUSPEND_HOLD_COMPLETE))) {
if (sys.state == STATE_HOLD && (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK)) {
sys.toggle_ovr_mask |= TOGGLE_OVR_STOP_RESTORE_CYCLE; // Set to restore in suspend routine and cycle start after.
} else { } 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)) {
@ -383,31 +363,178 @@ 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_START) {
// // Block if called at same time as the hold commands: feed hold, motion cancel, and safety door.
// // Ensures auto-cycle-start doesn't resume a hold without an explicit user-input.
// if (!(rt_exec & (EXEC_FEED_HOLD | EXEC_MOTION_CANCEL | EXEC_SAFETY_DOOR))) {
// // Cycle start only when IDLE or when a hold is complete and ready to resume.
// // NOTE: SAFETY_DOOR is implicitly blocked. It reverts to HOLD when the door is closed.
// if ((sys.state == STATE_IDLE) || ((sys.state & STATE_HOLD) && (sys.suspend & SUSPEND_HOLD_COMPLETE))) {
// if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
// if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
// 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.
// 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)) {
// sys.suspend = SUSPEND_DISABLE; // Break suspend state.
// sys.state = STATE_CYCLE;
// st_prep_buffer(); // Initialize step segment buffer before beginning cycle.
// st_wake_up();
// } else { // Otherwise, do nothing. Set and resume IDLE state.
// sys.suspend = SUSPEND_DISABLE; // Break suspend state.
// sys.state = STATE_IDLE;
// }
// }
// }
// }
// 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)) && !(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 {
// Motion complete. Includes CYCLE/JOG/HOMING states and jog cancel/motion cancel/soft limit events.
// 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.suspend = SUSPEND_DISABLE;
sys.state = STATE_IDLE; 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) {
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_JOG)) {
st_prep_buffer(); st_prep_buffer();
} }
@ -426,27 +553,57 @@ 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; }
// Block until initial hold is complete and the machine has stopped motion.
if (sys.suspend & SUSPEND_HOLD_COMPLETE) {
// Safety door manager. Handles de/re-energizing, switch state checks, and parking motions. // 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)) { if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
// Handles retraction motions and de-energizing. // Handles retraction motions and de-energizing.
if (bit_isfalse(sys.suspend,SUSPEND_RETRACT_COMPLETE)) { if (bit_isfalse(sys.suspend,SUSPEND_RETRACT_COMPLETE)) {
// Ensure any prior spindle stop override is disabled at start of safety door routine.
bit_false(sys.toggle_ovr_mask,TOGGLE_OVR_STOP_ACTIVE_MASK);
#ifndef PARKING_ENABLE #ifndef PARKING_ENABLE
spindle_stop(); // De-energize spindle_stop(); // De-energize
coolant_stop(); // De-energize coolant_set_state(COOLANT_DISABLE); // De-energize
#else #else
// Get current position and store restore location and spindle retract waypoint. // Get current position and store restore location and spindle retract waypoint.
system_convert_array_steps_to_mpos(parking_target,sys.position); system_convert_array_steps_to_mpos(parking_target,sys_position);
if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) { if (bit_isfalse(sys.suspend,SUSPEND_RESTART_RETRACT)) {
memcpy(restore_target,parking_target,sizeof(parking_target)); memcpy(restore_target,parking_target,sizeof(parking_target));
retract_waypoint += restore_target[PARKING_AXIS]; retract_waypoint += restore_target[PARKING_AXIS];
@ -463,23 +620,25 @@ static void protocol_exec_rt_suspend()
// the workpiece and waypoint motion doesn't exceed the parking target location. // the workpiece and waypoint motion doesn't exceed the parking target location.
if (parking_target[PARKING_AXIS] < retract_waypoint) { 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_PULLOUT_RATE); pl_data->feed_rate = PARKING_PULLOUT_RATE;
mc_parking_motion(parking_target, pl_data);
} }
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. // Execute fast parking retract motion to parking target location.
if (parking_target[PARKING_AXIS] < PARKING_TARGET) { if (parking_target[PARKING_AXIS] < PARKING_TARGET) {
parking_target[PARKING_AXIS] = PARKING_TARGET; parking_target[PARKING_AXIS] = PARKING_TARGET;
mc_parking_motion(parking_target, PARKING_RATE); pl_data->feed_rate = PARKING_RATE;
mc_parking_motion(parking_target, pl_data);
} }
} else { } else {
// Parking motion not possible. Just disable the spindle and coolant. // Parking motion not possible. Just disable the spindle and coolant.
spindle_stop(); // De-energize spindle_stop(); // De-energize
coolant_stop(); // De-energize coolant_set_state(COOLANT_DISABLE); // De-energize
} }
@ -494,7 +653,7 @@ static void protocol_exec_rt_suspend()
// NOTE: This unlocks the SAFETY_DOOR state to a HOLD state, such that CYCLE_START can activate a 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 (sys.state == STATE_SAFETY_DOOR) {
if (!(system_check_safety_door_ajar())) { if (!(system_check_safety_door_ajar())) {
sys.state = STATE_HOLD; // Update to HOLD state to indicate door is closed and ready to resume. sys.suspend &= ~(SUSPEND_SAFETY_DOOR_AJAR); // Reset door ajar flag to denote ready to resume.
} }
} }
@ -508,7 +667,8 @@ static void protocol_exec_rt_suspend()
// Check to ensure the motion doesn't move below pull-out position. // Check to ensure the motion doesn't move below pull-out position.
if (parking_target[PARKING_AXIS] <= PARKING_TARGET) { if (parking_target[PARKING_AXIS] <= PARKING_TARGET) {
parking_target[PARKING_AXIS] = retract_waypoint; parking_target[PARKING_AXIS] = retract_waypoint;
mc_parking_motion(parking_target, PARKING_RATE); pl_data->feed_rate = PARKING_RATE;
mc_parking_motion(parking_target, pl_data);
} }
} }
#endif #endif
@ -517,15 +677,15 @@ static void protocol_exec_rt_suspend()
if (gc_state.modal.spindle != SPINDLE_DISABLE) { 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)) {
spindle_set_state(gc_state.modal.spindle, gc_state.spindle_speed); 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_SAFETY_DOOR); delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
} }
} }
if (gc_state.modal.coolant != COOLANT_DISABLE) { if (gc_state.modal.coolant != COOLANT_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)) {
coolant_set_state(gc_state.modal.coolant); coolant_set_state((restore_condition & (PL_COND_FLAG_COOLANT_FLOOD | PL_COND_FLAG_COOLANT_FLOOD)));
delay_sec(SAFETY_DOOR_COOLANT_DELAY, DELAY_MODE_SAFETY_DOOR); delay_sec(SAFETY_DOOR_COOLANT_DELAY, DELAY_MODE_SYS_SUSPEND);
} }
} }
@ -537,7 +697,8 @@ static void protocol_exec_rt_suspend()
// Regardless if the retract parking motion was a valid/safe motion or not, the // 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 // restore parking motion should logically be valid, either by returning to the
// original position through valid machine space or by not moving at all. // original position through valid machine space or by not moving at all.
mc_parking_motion(restore_target, PARKING_PULLOUT_RATE); pl_data->feed_rate = PARKING_PULLOUT_RATE;
mc_parking_motion(parking_target, pl_data);
} }
} }
#endif #endif
@ -549,8 +710,38 @@ static void protocol_exec_rt_suspend()
} }
} }
} 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);
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();
} }
} }

View File

@ -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
@ -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();

View File

@ -2,7 +2,7 @@
report.c - reporting and messaging methods report.c - 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
@ -39,13 +39,15 @@
// TODO: Install silent mode to return only numeric values, primarily for GUIs. // TODO: Install silent mode to return only numeric values, primarily for GUIs.
void report_status_message(uint8_t status_code) void report_status_message(uint8_t status_code)
{ {
if (status_code == 0) { // STATUS_OK switch(status_code) {
printPgmString(PSTR("ok\r\n")); case STATUS_OK: // STATUS_OK
} else { printPgmString(PSTR("ok\r\n")); break;
printPgmString(PSTR("error: ")); default:
#ifdef REPORT_GUI_MODE #ifdef REPORT_GUI_MODE
printPgmString(PSTR("error:"));
print_uint8_base10(status_code); print_uint8_base10(status_code);
#else #else
printPgmString(PSTR("error: "));
switch(status_code) { switch(status_code) {
case STATUS_EXPECTED_COMMAND_LETTER: case STATUS_EXPECTED_COMMAND_LETTER:
printPgmString(PSTR("Expected command letter")); break; printPgmString(PSTR("Expected command letter")); break;
@ -63,8 +65,8 @@ void report_status_message(uint8_t status_code)
printPgmString(PSTR("EEPROM read fail. Using defaults")); break; printPgmString(PSTR("EEPROM read fail. Using defaults")); break;
case STATUS_IDLE_ERROR: case STATUS_IDLE_ERROR:
printPgmString(PSTR("Not idle")); break; printPgmString(PSTR("Not idle")); break;
case STATUS_ALARM_LOCK: case STATUS_SYSTEM_GC_LOCK:
printPgmString(PSTR("Alarm lock")); break; printPgmString(PSTR("G-code lock")); break;
case STATUS_SOFT_LIMIT_ERROR: case STATUS_SOFT_LIMIT_ERROR:
printPgmString(PSTR("Homing not enabled")); break; printPgmString(PSTR("Homing not enabled")); break;
case STATUS_OVERFLOW: case STATUS_OVERFLOW:
@ -75,11 +77,17 @@ void report_status_message(uint8_t status_code)
#endif #endif
case STATUS_CHECK_DOOR: case STATUS_CHECK_DOOR:
printPgmString(PSTR("Check Door")); break; printPgmString(PSTR("Check Door")); break;
// case STATUS_LINE_LENGTH_EXCEEDED: // Supported on Grbl-Mega only.
// printPgmString(PSTR("Line length exceeded")); break;
case STATUS_TRAVEL_EXCEEDED:
printPgmString(PSTR("Travel exceeded")); break;
case STATUS_INVALID_JOG_COMMAND:
printPgmString(PSTR("Invalid jog command")); break;
// Common g-code parser errors. // Common g-code parser errors.
case STATUS_GCODE_MODAL_GROUP_VIOLATION:
printPgmString(PSTR("Modal group violation")); break;
case STATUS_GCODE_UNSUPPORTED_COMMAND: case STATUS_GCODE_UNSUPPORTED_COMMAND:
printPgmString(PSTR("Unsupported command")); break; printPgmString(PSTR("Unsupported command")); break;
case STATUS_GCODE_MODAL_GROUP_VIOLATION:
printPgmString(PSTR("Modal group violation")); break;
case STATUS_GCODE_UNDEFINED_FEED_RATE: case STATUS_GCODE_UNDEFINED_FEED_RATE:
printPgmString(PSTR("Undefined feed rate")); break; printPgmString(PSTR("Undefined feed rate")); break;
default: default:
@ -95,10 +103,11 @@ void report_status_message(uint8_t status_code)
// Prints alarm messages. // Prints alarm messages.
void report_alarm_message(int8_t alarm_code) void report_alarm_message(int8_t alarm_code)
{ {
printPgmString(PSTR("ALARM: "));
#ifdef REPORT_GUI_MODE #ifdef REPORT_GUI_MODE
printPgmString(PSTR("ALARM:"));
print_uint8_base10(alarm_code); print_uint8_base10(alarm_code);
#else #else
printPgmString(PSTR("ALARM: "));
switch (alarm_code) { switch (alarm_code) {
case ALARM_HARD_LIMIT_ERROR: case ALARM_HARD_LIMIT_ERROR:
printPgmString(PSTR("Hard limit")); break; printPgmString(PSTR("Hard limit")); break;
@ -106,9 +115,13 @@ void report_alarm_message(int8_t alarm_code)
printPgmString(PSTR("Soft limit")); break; printPgmString(PSTR("Soft limit")); break;
case ALARM_ABORT_CYCLE: case ALARM_ABORT_CYCLE:
printPgmString(PSTR("Abort during cycle")); break; printPgmString(PSTR("Abort during cycle")); break;
case ALARM_PROBE_FAIL: case ALARM_PROBE_FAIL_INITIAL:
case ALARM_PROBE_FAIL_CONTACT:
printPgmString(PSTR("Probe fail")); break; printPgmString(PSTR("Probe fail")); break;
case ALARM_HOMING_FAIL: case ALARM_HOMING_FAIL_RESET:
case ALARM_HOMING_FAIL_DOOR:
case ALARM_HOMING_FAIL_PULLOFF:
case ALARM_HOMING_FAIL_APPROACH:
printPgmString(PSTR("Homing fail")); break; printPgmString(PSTR("Homing fail")); break;
} }
#endif #endif
@ -124,24 +137,27 @@ void report_alarm_message(int8_t alarm_code)
// TODO: Install silence feedback messages option in settings // TODO: Install silence feedback messages option in settings
void report_feedback_message(uint8_t message_code) void report_feedback_message(uint8_t message_code)
{ {
printPgmString(PSTR("["));
switch(message_code) { switch(message_code) {
case MESSAGE_CRITICAL_EVENT: case MESSAGE_CRITICAL_EVENT:
printPgmString(PSTR("Reset to continue")); break; printPgmString(PSTR("[Reset to continue")); break;
case MESSAGE_ALARM_LOCK: case MESSAGE_ALARM_LOCK:
printPgmString(PSTR("'$H'|'$X' to unlock")); break; printPgmString(PSTR("['$H'|'$X' to unlock")); break;
case MESSAGE_ALARM_UNLOCK: case MESSAGE_ALARM_UNLOCK:
printPgmString(PSTR("Caution: Unlocked")); break; printPgmString(PSTR("[Caution: Unlocked")); break;
case MESSAGE_ENABLED: case MESSAGE_ENABLED:
printPgmString(PSTR("Enabled")); break; printPgmString(PSTR("[Enabled")); break;
case MESSAGE_DISABLED: case MESSAGE_DISABLED:
printPgmString(PSTR("Disabled")); break; printPgmString(PSTR("[Disabled")); break;
case MESSAGE_SAFETY_DOOR_AJAR: case MESSAGE_SAFETY_DOOR_AJAR:
printPgmString(PSTR("Check Door")); break; printPgmString(PSTR("[Check Door")); break;
case MESSAGE_CHECK_LIMITS:
printPgmString(PSTR("[Check Limits")); break;
case MESSAGE_PROGRAM_END: case MESSAGE_PROGRAM_END:
printPgmString(PSTR("Pgm End")); break; printPgmString(PSTR("[Pgm End")); break;
case MESSAGE_RESTORE_DEFAULTS: case MESSAGE_RESTORE_DEFAULTS:
printPgmString(PSTR("Restoring defaults")); break; printPgmString(PSTR("[Restoring defaults")); break;
case MESSAGE_SPINDLE_RESTORE:
printPgmString(PSTR("[Restoring spindle")); break;
} }
printPgmString(PSTR("]\r\n")); printPgmString(PSTR("]\r\n"));
} }
@ -155,7 +171,9 @@ void report_init_message()
// Grbl help message // Grbl help message
void report_grbl_help() { void report_grbl_help() {
#ifndef REPORT_GUI_MODE #ifdef REPORT_GUI_MODE
printPgmString(PSTR("[$$ $# $G $I $N $x=val $Nx=line $J=line $C $X $H ~ ! ? ctrl-x]\r\n"));
#else
printPgmString(PSTR("$$ (view Grbl settings)\r\n" printPgmString(PSTR("$$ (view Grbl settings)\r\n"
"$# (view # parameters)\r\n" "$# (view # parameters)\r\n"
"$G (view parser state)\r\n" "$G (view parser state)\r\n"
@ -163,6 +181,7 @@ void report_grbl_help() {
"$N (view startup blocks)\r\n" "$N (view startup blocks)\r\n"
"$x=value (save Grbl setting)\r\n" "$x=value (save Grbl setting)\r\n"
"$Nx=line (save startup block)\r\n" "$Nx=line (save startup block)\r\n"
"$J=line (jog)\r\n"
"$C (check gcode mode)\r\n" "$C (check gcode mode)\r\n"
"$X (kill alarm lock)\r\n" "$X (kill alarm lock)\r\n"
"$H (run homing cycle)\r\n" "$H (run homing cycle)\r\n"
@ -200,34 +219,39 @@ void report_grbl_settings() {
printPgmString(PSTR("\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff); printPgmString(PSTR("\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff);
printPgmString(PSTR("\r\n$30=")); printFloat_RPMValue(settings.rpm_max); printPgmString(PSTR("\r\n$30=")); printFloat_RPMValue(settings.rpm_max);
printPgmString(PSTR("\r\n$31=")); printFloat_RPMValue(settings.rpm_min); printPgmString(PSTR("\r\n$31=")); printFloat_RPMValue(settings.rpm_min);
printPgmString(PSTR("\r\n")); #ifdef VARIABLE_SPINDLE
printPgmString(PSTR("\r\n$32=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_LASER_MODE));
#else
printPgmString(PSTR("\r\n$32=0\r\n"));
#endif
#else #else
printPgmString(PSTR("$0=")); print_uint8_base10(settings.pulse_microseconds); printPgmString(PSTR("$0=")); print_uint8_base10(settings.pulse_microseconds);
printPgmString(PSTR(" (step pulse, usec)\r\n$1=")); print_uint8_base10(settings.stepper_idle_lock_time); printPgmString(PSTR(" (step pulse, usec)\r\n$1=")); print_uint8_base10(settings.stepper_idle_lock_time);
printPgmString(PSTR(" (step idle delay, msec)\r\n$2=")); print_uint8_base10(settings.step_invert_mask); printPgmString(PSTR(" (step idle delay, msec)\r\n$2=")); print_uint8_base10(settings.step_invert_mask);
printPgmString(PSTR(" (step port invert mask:")); print_uint8_base2(settings.step_invert_mask); printPgmString(PSTR(" (step port invert mask)\r\n$3=")); print_uint8_base10(settings.dir_invert_mask);
printPgmString(PSTR(")\r\n$3=")); print_uint8_base10(settings.dir_invert_mask); printPgmString(PSTR(" (dir port invert mask)\r\n$4=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
printPgmString(PSTR(" (dir port invert mask:")); print_uint8_base2(settings.dir_invert_mask);
printPgmString(PSTR(")\r\n$4=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
printPgmString(PSTR(" (step enable invert, bool)\r\n$5=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)); printPgmString(PSTR(" (step enable invert, bool)\r\n$5=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS));
printPgmString(PSTR(" (limit pins invert, bool)\r\n$6=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN)); printPgmString(PSTR(" (limit pins invert, bool)\r\n$6=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN));
printPgmString(PSTR(" (probe pin invert, bool)\r\n$10=")); print_uint8_base10(settings.status_report_mask); printPgmString(PSTR(" (probe pin invert, bool)\r\n$10=")); print_uint8_base10(settings.status_report_mask);
printPgmString(PSTR(" (status report mask:")); print_uint8_base2(settings.status_report_mask); printPgmString(PSTR(" (status report mask)\r\n$11=")); printFloat_SettingValue(settings.junction_deviation);
printPgmString(PSTR(")\r\n$11=")); printFloat_SettingValue(settings.junction_deviation);
printPgmString(PSTR(" (junction deviation, mm)\r\n$12=")); printFloat_SettingValue(settings.arc_tolerance); printPgmString(PSTR(" (junction deviation, mm)\r\n$12=")); printFloat_SettingValue(settings.arc_tolerance);
printPgmString(PSTR(" (arc tolerance, mm)\r\n$13=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)); printPgmString(PSTR(" (arc tolerance, mm)\r\n$13=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
printPgmString(PSTR(" (report inches, bool)\r\n$20=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE)); printPgmString(PSTR(" (report inches, bool)\r\n$20=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE));
printPgmString(PSTR(" (soft limits, bool)\r\n$21=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE)); printPgmString(PSTR(" (soft limits, bool)\r\n$21=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
printPgmString(PSTR(" (hard limits, bool)\r\n$22=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE)); printPgmString(PSTR(" (hard limits, bool)\r\n$22=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
printPgmString(PSTR(" (homing cycle, bool)\r\n$23=")); print_uint8_base10(settings.homing_dir_mask); printPgmString(PSTR(" (homing cycle, bool)\r\n$23=")); print_uint8_base10(settings.homing_dir_mask);
printPgmString(PSTR(" (homing dir invert mask:")); print_uint8_base2(settings.homing_dir_mask); printPgmString(PSTR(" (homing dir invert mask\r\n$24=")); printFloat_SettingValue(settings.homing_feed_rate);
printPgmString(PSTR(")\r\n$24=")); printFloat_SettingValue(settings.homing_feed_rate);
printPgmString(PSTR(" (homing feed, mm/min)\r\n$25=")); printFloat_SettingValue(settings.homing_seek_rate); printPgmString(PSTR(" (homing feed, mm/min)\r\n$25=")); printFloat_SettingValue(settings.homing_seek_rate);
printPgmString(PSTR(" (homing seek, mm/min)\r\n$26=")); print_uint8_base10(settings.homing_debounce_delay); printPgmString(PSTR(" (homing seek, mm/min)\r\n$26=")); print_uint8_base10(settings.homing_debounce_delay);
printPgmString(PSTR(" (homing debounce, msec)\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff); printPgmString(PSTR(" (homing debounce, msec)\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff);
printPgmString(PSTR(" (homing pull-off, mm)\r\n$30=")); printFloat_RPMValue(settings.rpm_max); printPgmString(PSTR(" (homing pull-off, mm)\r\n$30=")); printFloat_RPMValue(settings.rpm_max);
printPgmString(PSTR(" (rpm max)\r\n$31=")); printFloat_RPMValue(settings.rpm_min); printPgmString(PSTR(" (rpm max)\r\n$31=")); printFloat_RPMValue(settings.rpm_min);
printPgmString(PSTR(" (rpm min)\r\n")); #ifdef VARIABLE_SPINDLE
printPgmString(PSTR(" (rpm min)\r\n$32=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_LASER_MODE));
printPgmString(PSTR(" (laser mode, bool)\r\n"));
#else
printPgmString(PSTR(" (rpm min)\r\n$32=0 (laser mode, bool)\r\n"));
#endif
#endif #endif
// Print axis settings // Print axis settings
@ -235,9 +259,9 @@ void report_grbl_settings() {
uint8_t val = AXIS_SETTINGS_START_VAL; uint8_t val = AXIS_SETTINGS_START_VAL;
for (set_idx=0; set_idx<AXIS_N_SETTINGS; set_idx++) { for (set_idx=0; set_idx<AXIS_N_SETTINGS; set_idx++) {
for (idx=0; idx<N_AXIS; idx++) { for (idx=0; idx<N_AXIS; idx++) {
printPgmString(PSTR("$")); serial_write('$');
print_uint8_base10(val+idx); print_uint8_base10(val+idx);
printPgmString(PSTR("=")); serial_write('=');
switch (set_idx) { switch (set_idx) {
case 0: printFloat_SettingValue(settings.steps_per_mm[idx]); break; case 0: printFloat_SettingValue(settings.steps_per_mm[idx]); break;
case 1: printFloat_SettingValue(settings.max_rate[idx]); break; case 1: printFloat_SettingValue(settings.max_rate[idx]); break;
@ -247,7 +271,8 @@ void report_grbl_settings() {
#ifdef REPORT_GUI_MODE #ifdef REPORT_GUI_MODE
printPgmString(PSTR("\r\n")); printPgmString(PSTR("\r\n"));
#else #else
printPgmString(PSTR(" (")); serial_write(' ');
serial_write('(');
switch (idx) { switch (idx) {
case X_AXIS: printPgmString(PSTR("x")); break; case X_AXIS: printPgmString(PSTR("x")); break;
case Y_AXIS: printPgmString(PSTR("y")); break; case Y_AXIS: printPgmString(PSTR("y")); break;
@ -278,11 +303,11 @@ void report_probe_parameters()
// Report in terms of machine position. // Report in terms of machine position.
printPgmString(PSTR("[PRB:")); printPgmString(PSTR("[PRB:"));
for (i=0; i< N_AXIS; i++) { for (i=0; i< N_AXIS; i++) {
print_position[i] = system_convert_axis_steps_to_mpos(sys.probe_position,i); print_position[i] = system_convert_axis_steps_to_mpos(sys_probe_position,i);
printFloat_CoordValue(print_position[i]); printFloat_CoordValue(print_position[i]);
if (i < (N_AXIS-1)) { printPgmString(PSTR(",")); } if (i < (N_AXIS-1)) { serial_write(','); }
} }
printPgmString(PSTR(":")); serial_write(':');
print_uint8_base10(sys.probe_succeeded); print_uint8_base10(sys.probe_succeeded);
printPgmString(PSTR("]\r\n")); printPgmString(PSTR("]\r\n"));
} }
@ -304,17 +329,17 @@ void report_ngc_parameters()
case 7: printPgmString(PSTR("30")); break; case 7: printPgmString(PSTR("30")); break;
default: print_uint8_base10(coord_select+54); break; // G54-G59 default: print_uint8_base10(coord_select+54); break; // G54-G59
} }
printPgmString(PSTR(":")); serial_write(':');
for (i=0; i<N_AXIS; i++) { for (i=0; i<N_AXIS; i++) {
printFloat_CoordValue(coord_data[i]); printFloat_CoordValue(coord_data[i]);
if (i < (N_AXIS-1)) { printPgmString(PSTR(",")); } if (i < (N_AXIS-1)) { serial_write(','); }
else { printPgmString(PSTR("]\r\n")); } else { printPgmString(PSTR("]\r\n")); }
} }
} }
printPgmString(PSTR("[G92:")); // Print G92,G92.1 which are not persistent in memory printPgmString(PSTR("[G92:")); // Print G92,G92.1 which are not persistent in memory
for (i=0; i<N_AXIS; i++) { for (i=0; i<N_AXIS; i++) {
printFloat_CoordValue(gc_state.coord_offset[i]); printFloat_CoordValue(gc_state.coord_offset[i]);
if (i < (N_AXIS-1)) { printPgmString(PSTR(",")); } if (i < (N_AXIS-1)) { serial_write(','); }
else { printPgmString(PSTR("]\r\n")); } else { printPgmString(PSTR("]\r\n")); }
} }
printPgmString(PSTR("[TLO:")); // Print tool length offset value printPgmString(PSTR("[TLO:")); // Print tool length offset value
@ -327,16 +352,14 @@ void report_ngc_parameters()
// Print current gcode parser mode state // Print current gcode parser mode state
void report_gcode_modes() void report_gcode_modes()
{ {
printPgmString(PSTR("["));
switch (gc_state.modal.motion) { switch (gc_state.modal.motion) {
case MOTION_MODE_SEEK : printPgmString(PSTR("G0")); break; case MOTION_MODE_SEEK : printPgmString(PSTR("[G0")); break;
case MOTION_MODE_LINEAR : printPgmString(PSTR("G1")); break; case MOTION_MODE_LINEAR : printPgmString(PSTR("[G1")); break;
case MOTION_MODE_CW_ARC : printPgmString(PSTR("G2")); break; case MOTION_MODE_CW_ARC : printPgmString(PSTR("[G2")); break;
case MOTION_MODE_CCW_ARC : printPgmString(PSTR("G3")); break; case MOTION_MODE_CCW_ARC : printPgmString(PSTR("[G3")); break;
case MOTION_MODE_NONE : printPgmString(PSTR("G80")); break; case MOTION_MODE_NONE : printPgmString(PSTR("[G80")); break;
default: default:
printPgmString(PSTR("G38.")); printPgmString(PSTR("[G38."));
print_uint8_base10(gc_state.modal.motion - (MOTION_MODE_PROBE_TOWARD-2)); print_uint8_base10(gc_state.modal.motion - (MOTION_MODE_PROBE_TOWARD-2));
} }
@ -370,13 +393,15 @@ void report_gcode_modes()
case SPINDLE_DISABLE : printPgmString(PSTR(" M5")); break; case SPINDLE_DISABLE : printPgmString(PSTR(" M5")); break;
} }
switch (gc_state.modal.coolant) {
case COOLANT_DISABLE : printPgmString(PSTR(" M9")); break;
case COOLANT_FLOOD_ENABLE : printPgmString(PSTR(" M8")); break;
#ifdef ENABLE_M7 #ifdef ENABLE_M7
case COOLANT_MIST_ENABLE : printPgmString(PSTR(" M7")); break; if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST) { printPgmString(PSTR(" M7")); }
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD) { printPgmString(PSTR(" M8")); }
} else { printPgmString(PSTR(" M9")); }
#else
if (gc_state.modal.coolant) { printPgmString(PSTR(" M8")); }
else { printPgmString(PSTR(" M9")); }
#endif #endif
}
printPgmString(PSTR(" T")); printPgmString(PSTR(" T"));
print_uint8_base10(gc_state.tool); print_uint8_base10(gc_state.tool);
@ -395,8 +420,10 @@ void report_gcode_modes()
// Prints specified startup line // Prints specified startup line
void report_startup_line(uint8_t n, char *line) void report_startup_line(uint8_t n, char *line)
{ {
printPgmString(PSTR("$N")); print_uint8_base10(n); printPgmString(PSTR("$N"));
printPgmString(PSTR("=")); printString(line); print_uint8_base10(n);
serial_write('=');
printString(line);
printPgmString(PSTR("\r\n")); printPgmString(PSTR("\r\n"));
} }
@ -426,25 +453,34 @@ void report_echo_line_received(char *line)
// especially during g-code programs with fast, short line segments and high frequency reports (5-20Hz). // especially during g-code programs with fast, short line segments and high frequency reports (5-20Hz).
void report_realtime_status() void report_realtime_status()
{ {
// **Under construction** Bare-bones status report. Provides real-time machine position relative to #ifdef USE_CLASSIC_REALTIME_REPORT
// the system power on location (0,0,0) and work coordinate position (G54 and G92 applied). Eventually
// to be added are distance to go on block, processed block id, and feed rate. Also a settings bitmask
// for a user to select the desired real-time data.
uint8_t idx; uint8_t idx;
int32_t current_position[N_AXIS]; // Copy current state of the system position variable int32_t current_position[N_AXIS]; // Copy current state of the system position variable
memcpy(current_position,sys.position,sizeof(sys.position)); memcpy(current_position,sys_position,sizeof(sys_position));
float print_position[N_AXIS]; float print_position[N_AXIS];
// Report current machine state // Report current machine state
switch (sys.state) { switch (sys.state) {
case STATE_IDLE: printPgmString(PSTR("<Idle")); break; case STATE_IDLE: printPgmString(PSTR("<Idle")); break;
case STATE_MOTION_CANCEL: // Report run state.
case STATE_CYCLE: printPgmString(PSTR("<Run")); break; case STATE_CYCLE: printPgmString(PSTR("<Run")); break;
case STATE_HOLD: printPgmString(PSTR("<Hold")); break; case STATE_HOLD:
if (!(sys.suspend & SUSPEND_JOG_CANCEL)) {
printPgmString(PSTR("<Hold"));
break;
} // Continues to print jog state during jog cancel.
case STATE_JOG: printPgmString(PSTR("<Jog")); break;
case STATE_HOMING: printPgmString(PSTR("<Home")); break; case STATE_HOMING: printPgmString(PSTR("<Home")); break;
case STATE_ALARM: printPgmString(PSTR("<Alarm")); break; case STATE_ALARM: printPgmString(PSTR("<Alarm")); break;
case STATE_CHECK_MODE: printPgmString(PSTR("<Check")); break; case STATE_CHECK_MODE: printPgmString(PSTR("<Check")); break;
case STATE_SAFETY_DOOR: printPgmString(PSTR("<Door")); break; case STATE_SAFETY_DOOR:
if (!(sys.suspend & SUSPEND_RETRACT_COMPLETE)) {
printPgmString(PSTR("<Door"));
} else {
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) { printPgmString(PSTR("<Door")); }
else { printPgmString(PSTR("<Hold")); }
}
break;
} }
// If reporting a position, convert the current step count (current_position) to millimeters. // If reporting a position, convert the current step count (current_position) to millimeters.
@ -457,7 +493,7 @@ void report_realtime_status()
printPgmString(PSTR(",MPos:")); printPgmString(PSTR(",MPos:"));
for (idx=0; idx< N_AXIS; idx++) { for (idx=0; idx< N_AXIS; idx++) {
printFloat_CoordValue(print_position[idx]); printFloat_CoordValue(print_position[idx]);
if (idx < (N_AXIS-1)) { printPgmString(PSTR(",")); } if (idx < (N_AXIS-1)) { serial_write(','); }
} }
} }
@ -469,7 +505,7 @@ void report_realtime_status()
print_position[idx] -= gc_state.coord_system[idx]+gc_state.coord_offset[idx]; print_position[idx] -= gc_state.coord_system[idx]+gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { print_position[idx] -= gc_state.tool_length_offset; } if (idx == TOOL_LENGTH_OFFSET_AXIS) { print_position[idx] -= gc_state.tool_length_offset; }
printFloat_CoordValue(print_position[idx]); printFloat_CoordValue(print_position[idx]);
if (idx < (N_AXIS-1)) { printPgmString(PSTR(",")); } if (idx < (N_AXIS-1)) { serial_write(','); }
} }
} }
@ -507,7 +543,7 @@ void report_realtime_status()
( BITFLAG_RT_STATUS_LIMIT_PINS| BITFLAG_RT_STATUS_PROBE_PIN | BITFLAG_RT_STATUS_CONTROL_PINS ))) { ( BITFLAG_RT_STATUS_LIMIT_PINS| BITFLAG_RT_STATUS_PROBE_PIN | BITFLAG_RT_STATUS_CONTROL_PINS ))) {
printPgmString(PSTR(",Pin:")); printPgmString(PSTR(",Pin:"));
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_LIMIT_PINS)) { if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_LIMIT_PINS)) {
print_unsigned_int8(limits_get_state(),2,N_AXIS); print_uint8_base2_ndigit(limits_get_state(),N_AXIS);
} }
printPgmString(PSTR("|")); printPgmString(PSTR("|"));
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_PROBE_PIN)) { if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_PROBE_PIN)) {
@ -516,15 +552,202 @@ void report_realtime_status()
} }
printPgmString(PSTR("|")); printPgmString(PSTR("|"));
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_CONTROL_PINS)) { if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_CONTROL_PINS)) {
print_unsigned_int8(system_control_get_state(),2,N_CONTROL_PIN); print_uint8_base2_ndigit(system_control_get_state(),N_CONTROL_PIN);
} }
} }
#else #else
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_LIMIT_PINS)) { if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_LIMIT_PINS)) {
printPgmString(PSTR(",Lim:")); printPgmString(PSTR(",Lim:"));
print_unsigned_int8(limits_get_state(),2,N_AXIS); print_uint8_base2_ndigit(limits_get_state(),N_AXIS);
}
#endif
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_OVERRIDES)) {
printPgmString(PSTR(",Ov:"));
print_uint8_base10(sys.f_override);
serial_write(',');
print_uint8_base10(sys.r_override);
serial_write(',');
print_uint8_base10(sys.spindle_speed_ovr);
if (sys.toggle_ovr_mask) {
printPgmString(PSTR("|T:"));
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK) { serial_write('S'); }
if (sys.toggle_ovr_mask & TOGGLE_OVR_FLOOD_COOLANT) { serial_write('F'); }
#ifdef ENABLE_M7
if (sys.toggle_ovr_mask & TOGGLE_OVR_MIST_COOLANT) { serial_write('M'); }
#endif
bit_false(sys.toggle_ovr_mask, (TOGGLE_OVR_FLOOD_COOLANT|TOGGLE_OVR_FLOOD_COOLANT));
}
}
printPgmString(PSTR(">\r\n"));
#else
uint8_t idx;
int32_t current_position[N_AXIS]; // Copy current state of the system position variable
memcpy(current_position,sys_position,sizeof(sys_position));
float print_position[N_AXIS];
system_convert_array_steps_to_mpos(print_position,current_position);
// Report current machine state and sub-states
switch (sys.state) {
case STATE_IDLE: printPgmString(PSTR("<Idle")); break;
case STATE_CYCLE: printPgmString(PSTR("<Run")); break;
case STATE_HOLD:
if (!(sys.suspend & SUSPEND_JOG_CANCEL)) {
printPgmString(PSTR("<Hold:"));
if (sys.suspend & SUSPEND_HOLD_COMPLETE) { serial_write('0'); } // Ready to resume
else { serial_write('1'); } // Actively holding
break;
} // Continues to print jog state during jog cancel.
case STATE_JOG: printPgmString(PSTR("<Jog")); break;
case STATE_HOMING: printPgmString(PSTR("<Home")); break;
case STATE_ALARM: printPgmString(PSTR("<Alarm")); break;
case STATE_CHECK_MODE: printPgmString(PSTR("<Check")); break;
case STATE_SAFETY_DOOR:
printPgmString(PSTR("<Door:"));
if (sys.suspend & SUSPEND_INITIATE_RESTORE) {
serial_write('3'); // Restoring
} else {
if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
serial_write('1'); // Door ajar
} else {
serial_write('0');
} // Door closed and ready to resume
} else {
serial_write('2'); // Retracting
}
}
break;
// case STATE_SLEEP: printPgmString(PSTR("<Sleep:")); // [Grbl-Mega Only]
// if (sys.suspend & SUSPEND_RETRACT_COMPLETE) { printPgmString(PSTR("0")); } // Parked
// else { printPgmString(PSTR("1")); } // Actively holding and retracting
// break;
}
// Report machine position
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_POSITION_TYPE)) {
printPgmString(PSTR("|MPos:"));
} else {
// Report work position
printPgmString(PSTR("|WPos:"));
for (idx=0; idx< N_AXIS; idx++) {
// Apply work coordinate offsets and tool length offset to current position.
print_position[idx] -= gc_state.coord_system[idx]+gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { print_position[idx] -= gc_state.tool_length_offset; }
}
}
for (idx=0; idx< N_AXIS; idx++) {
printFloat_CoordValue(print_position[idx]);
if (idx < (N_AXIS-1)) { serial_write(','); }
}
// Returns planner and serial read buffer states.
#ifdef REPORT_FIELD_BUFFER_STATE
printPgmString(PSTR("|Bf:"));
print_uint8_base10(plan_get_block_buffer_count());
serial_write(',');
print_uint8_base10(serial_get_rx_buffer_count());
#endif
#ifdef USE_LINE_NUMBERS
#ifdef REPORT_FIELD_LINE_NUMBERS
// Report current line number
plan_block_t * cur_block = plan_get_current_block();
if (cur_block != NULL) {
uint32_t ln = cur_block->line_number;
if (ln > 0) {
printPgmString(PSTR("|Ln:"));
printInteger(ln);
}
}
#endif
#endif
// Report realtime rate
#ifdef REPORT_FIELD_CURRENT_RATE
printPgmString(PSTR("|F:"));
printFloat_RateValue(st_get_realtime_rate());
#endif
#ifdef REPORT_FIELD_PIN_STATE
uint8_t lim_pin_state = limits_get_state();
uint8_t ctrl_pin_state = system_control_get_state();
uint8_t prb_pin_state = probe_get_state();
if (lim_pin_state | ctrl_pin_state | prb_pin_state) {
printPgmString(PSTR("|Pn:"));
if (prb_pin_state) { serial_write('P'); }
if (lim_pin_state) {
if (bit_istrue(lim_pin_state,bit(X_AXIS))) { serial_write('X'); }
if (bit_istrue(lim_pin_state,bit(Y_AXIS))) { serial_write('Y'); }
if (bit_istrue(lim_pin_state,bit(Z_AXIS))) { serial_write('Z'); }
}
if (ctrl_pin_state) {
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_SAFETY_DOOR)) { serial_write('D'); }
#endif
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_RESET)) { serial_write('R'); }
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_FEED_HOLD)) { serial_write('H'); }
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_CYCLE_START)) { serial_write('S'); }
}
}
#endif
#ifdef REPORT_FIELD_WORK_COORD_OFFSET
if (sys.report_wco_counter++ >= REPORT_WCO_REFRESH_BUSY_COUNT) {
if (sys.state & (STATE_HOMING | STATE_CYCLE | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)) {
sys.report_wco_counter = 1; // Reset counter for slow refresh
} else { sys.report_wco_counter = (REPORT_WCO_REFRESH_BUSY_COUNT-REPORT_WCO_REFRESH_IDLE_COUNT+1); }
if (sys.report_ovr_counter >= REPORT_OVR_REFRESH_BUSY_COUNT) {
sys.report_ovr_counter = (REPORT_OVR_REFRESH_BUSY_COUNT-1); // Set override on next report.
}
printPgmString(PSTR("|WCO:"));
float axis_offset;
uint8_t idx;
for (idx=0; idx<N_AXIS; idx++) {
axis_offset = gc_state.coord_system[idx]+gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { axis_offset += gc_state.tool_length_offset; }
printFloat_CoordValue(axis_offset);
if (idx < (N_AXIS-1)) { serial_write(','); }
}
}
#endif
#ifdef REPORT_FIELD_OVERRIDES
if (sys.report_ovr_counter++ >= REPORT_OVR_REFRESH_BUSY_COUNT) {
if (sys.state & (STATE_HOMING | STATE_CYCLE | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)) {
sys.report_ovr_counter = 1; // Reset counter for slow refresh
} else { sys.report_ovr_counter = (REPORT_OVR_REFRESH_BUSY_COUNT-REPORT_OVR_REFRESH_IDLE_COUNT+1); }
printPgmString(PSTR("|Ov:"));
print_uint8_base10(sys.f_override);
serial_write(',');
print_uint8_base10(sys.r_override);
serial_write(',');
print_uint8_base10(sys.spindle_speed_ovr);
if (sys.toggle_ovr_mask) {
printPgmString(PSTR("|T:"));
if (sys.toggle_ovr_mask & TOGGLE_OVR_STOP_ACTIVE_MASK) { serial_write('S'); }
if (sys.toggle_ovr_mask & TOGGLE_OVR_FLOOD_COOLANT) { serial_write('F'); }
#ifdef ENABLE_M7
if (sys.toggle_ovr_mask & TOGGLE_OVR_MIST_COOLANT) { serial_write('M'); }
#endif
bit_false(sys.toggle_ovr_mask, (TOGGLE_OVR_FLOOD_COOLANT|TOGGLE_OVR_FLOOD_COOLANT));
}
} }
#endif #endif
printPgmString(PSTR(">\r\n")); printPgmString(PSTR(">\r\n"));
#endif
} }
#ifdef DEBUG
void report_realtime_debug()
{
}
#endif

View File

@ -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,28 @@
#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
// Prints system status messages. // Prints system status messages.
void report_status_message(uint8_t status_code); void report_status_message(uint8_t status_code);
@ -111,4 +120,8 @@ void report_startup_line(uint8_t n, char *line);
// 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

View File

@ -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,12 +21,14 @@
#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;
@ -39,9 +41,9 @@ volatile uint8_t serial_tx_buffer_tail = 0;
// Returns the number of bytes used in the RX serial buffer. // Returns the number of bytes used in the RX serial buffer.
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 diff = serial_rx_buffer_head-serial_rx_buffer_tail;
if (serial_rx_buffer_head >= rtail) { return(serial_rx_buffer_head-rtail); } if (diff >= 0) { return(diff); }
return (RX_BUFFER_SIZE - (rtail-serial_rx_buffer_head)); return (RX_RING_BUFFER + diff);
} }
@ -51,7 +53,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));
} }
@ -68,12 +70,8 @@ void serial_init()
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
} }
@ -84,7 +82,7 @@ void serial_init()
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) {
@ -121,7 +119,7 @@ ISR(SERIAL_UDRE)
// Update tail position // Update tail position
tail++; tail++;
if (tail == TX_BUFFER_SIZE) { tail = 0; } if (tail == TX_RING_BUFFER) { tail = 0; }
serial_tx_buffer_tail = tail; serial_tx_buffer_tail = tail;
} }
@ -141,7 +139,7 @@ uint8_t serial_read()
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 #ifdef ENABLE_XONXOFF
@ -162,16 +160,42 @@ ISR(SERIAL_RX)
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
default :
if (data > 0x7F) { // Real-time control characters are extended ACSII only.
switch(data) {
case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true
case CMD_RESET: mc_reset(); break; // Call motion control reset routine. #ifdef DEBUG
default: // Write character to buffer case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug,EXEC_DEBUG_REPORT); SREG = sreg;} break;
#endif
case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break;
case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break;
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;
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; next_head = serial_rx_buffer_head + 1;
if (next_head == RX_BUFFER_SIZE) { next_head = 0; } if (next_head == RX_RING_BUFFER) { next_head = 0; }
// Write data to buffer unless it is full. // Write data to buffer unless it is full.
if (next_head != serial_rx_buffer_tail) { if (next_head != serial_rx_buffer_tail) {
@ -186,7 +210,7 @@ ISR(SERIAL_RX)
#endif #endif
} }
//TODO: else alarm on overflow? }
} }
} }

View File

@ -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,7 +27,11 @@
#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

View File

@ -2,7 +2,7 @@
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,14 +27,21 @@ 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
// TODO: Alter the startup line parsing to prevent motions from being executed before this call.
// Implement it like the jog parsing.
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);
} }
@ -42,12 +49,16 @@ void settings_store_build_info(char *line)
// 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
// NOTE: This function can only be called in IDLE state.
void write_global_settings() void write_global_settings()
{ {
eeprom_put_char(0, SETTINGS_VERSION); eeprom_put_char(0, SETTINGS_VERSION);
@ -77,11 +88,13 @@ void settings_restore(uint8_t restore_flag) {
settings.flags = 0; settings.flags = 0;
if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; } if (DEFAULT_REPORT_INCHES) { settings.flags |= BITFLAG_REPORT_INCHES; }
if (DEFAULT_LASER_MODE) { settings.flags |= BITFLAG_LASER_MODE; }
if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; } if (DEFAULT_INVERT_ST_ENABLE) { settings.flags |= BITFLAG_INVERT_ST_ENABLE; }
if (DEFAULT_INVERT_LIMIT_PINS) { settings.flags |= BITFLAG_INVERT_LIMIT_PINS; }
if (DEFAULT_SOFT_LIMIT_ENABLE) { settings.flags |= BITFLAG_SOFT_LIMIT_ENABLE; }
if (DEFAULT_HARD_LIMIT_ENABLE) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; } if (DEFAULT_HARD_LIMIT_ENABLE) { settings.flags |= BITFLAG_HARD_LIMIT_ENABLE; }
if (DEFAULT_HOMING_ENABLE) { settings.flags |= BITFLAG_HOMING_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[X_AXIS] = DEFAULT_X_STEPS_PER_MM;
settings.steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM; settings.steps_per_mm[Y_AXIS] = DEFAULT_Y_STEPS_PER_MM;
@ -109,13 +122,18 @@ void settings_restore(uint8_t restore_flag) {
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);
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+1, 0); // Checksum
#endif #endif
#if N_STARTUP_LINE > 1 #if N_STARTUP_LINE > 1
eeprom_put_char(EEPROM_ADDR_STARTUP_BLOCK+(LINE_BUFFER_SIZE+1), 0); 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 #endif
} }
if (restore_flag & SETTINGS_RESTORE_BUILD_INFO) { eeprom_put_char(EEPROM_ADDR_BUILD_INFO , 0); } 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
}
} }
@ -238,6 +256,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;
@ -271,6 +290,14 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
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; break;
case 31: settings.rpm_min = value; break; case 31: settings.rpm_min = value; break;
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: default:
return(STATUS_INVALID_STATEMENT); return(STATUS_INVALID_STATEMENT);
} }
@ -287,18 +314,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.
} }

View File

@ -2,7 +2,7 @@
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
@ -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,20 +40,27 @@
#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)
#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

View File

@ -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,6 +22,18 @@
#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
#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
@ -37,6 +49,8 @@ void spindle_init()
SPINDLE_DIRECTION_DDR |= (1<<SPINDLE_DIRECTION_BIT); // Configure as output pin. SPINDLE_DIRECTION_DDR |= (1<<SPINDLE_DIRECTION_BIT); // Configure as output pin.
#endif #endif
pwm_gradient = SPINDLE_PWM_RANGE/(settings.rpm_max-settings.rpm_min);
#else #else
// Configure no variable spindle and only enable pin. // Configure no variable spindle and only enable pin.
@ -49,12 +63,13 @@ void spindle_init()
} }
void spindle_stop() // Stop and start spindle routines. Called by all spindle routines and stepper ISR.
inline 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
@ -71,7 +86,46 @@ void spindle_stop()
} }
void spindle_set_state(uint8_t state, float rpm) #ifdef VARIABLE_SPINDLE
inline 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
}
}
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.
@ -92,39 +146,7 @@ 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
@ -142,9 +164,14 @@ void spindle_set_state(uint8_t state, float rpm)
} }
// 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
} }

View File

@ -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
@ -26,12 +26,18 @@
// 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);
// Stop and start spindle routines. Called by all spindle routines and stepper ISR.
inline void spindle_stop();
inline 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.
// Kills spindle.
void spindle_stop();
#endif #endif

View File

@ -2,7 +2,7 @@
stepper.c - stepper motor driver: executes motion plans using stepper motors stepper.c - stepper motor driver: executes motion plans using stepper motors
Part of Grbl 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
@ -28,10 +28,12 @@
#define RAMP_ACCEL 0 #define RAMP_ACCEL 0
#define RAMP_CRUISE 1 #define RAMP_CRUISE 1
#define RAMP_DECEL 2 #define RAMP_DECEL 2
#define RAMP_DECEL_OVERRIDE 3
#define PREP_FLAG_RECALCULATE bit(0) #define PREP_FLAG_RECALCULATE bit(0)
#define PREP_FLAG_HOLD_PARTIAL_BLOCK bit(1) #define PREP_FLAG_HOLD_PARTIAL_BLOCK bit(1)
#define PREP_FLAG_PARKING bit(2) #define PREP_FLAG_PARKING bit(2)
#define PREP_FLAG_DECEL_OVERRIDE bit(3)
// Define Adaptive Multi-Axis Step-Smoothing(AMASS) levels and cutoff frequencies. The highest level // Define Adaptive Multi-Axis Step-Smoothing(AMASS) levels and cutoff frequencies. The highest level
// frequency bin starts at 0Hz and ends at its cutoff frequency. The next lower level frequency bin // frequency bin starts at 0Hz and ends at its cutoff frequency. The next lower level frequency bin
@ -57,6 +59,9 @@
// data for its own use. // data for its own use.
typedef struct { typedef struct {
uint8_t direction_bits; uint8_t direction_bits;
#ifdef VARIABLE_SPINDLE
uint8_t spindle_pwm;
#endif
uint32_t steps[N_AXIS]; uint32_t steps[N_AXIS];
uint32_t step_event_count; uint32_t step_event_count;
} st_block_t; } st_block_t;
@ -197,7 +202,6 @@ void st_wake_up()
if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) { STEPPERS_DISABLE_PORT |= (1<<STEPPERS_DISABLE_BIT); } if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) { STEPPERS_DISABLE_PORT |= (1<<STEPPERS_DISABLE_BIT); }
else { STEPPERS_DISABLE_PORT &= ~(1<<STEPPERS_DISABLE_BIT); } else { STEPPERS_DISABLE_PORT &= ~(1<<STEPPERS_DISABLE_BIT); }
// if (sys.state & (STATE_CYCLE | STATE_HOMING)){
// Initialize stepper output bits // Initialize stepper output bits
st.dir_outbits = dir_port_invert_mask; st.dir_outbits = dir_port_invert_mask;
st.step_outbits = step_port_invert_mask; st.step_outbits = step_port_invert_mask;
@ -215,7 +219,6 @@ void st_wake_up()
// Enable Stepper Driver Interrupt // Enable Stepper Driver Interrupt
TIMSK1 |= (1<<OCIE1A); TIMSK1 |= (1<<OCIE1A);
// }
} }
@ -346,6 +349,11 @@ ISR(TIMER1_COMPA_vect)
st.steps[Z_AXIS] = st.exec_block->steps[Z_AXIS] >> st.exec_segment->amass_level; st.steps[Z_AXIS] = st.exec_block->steps[Z_AXIS] >> st.exec_segment->amass_level;
#endif #endif
#ifdef VARIABLE_SPINDLE
// Set real-time spindle output as segment is loaded, just prior to the first step.
spindle_set_speed(st.exec_block->spindle_pwm);
#endif
} else { } else {
// Segment buffer empty. Shutdown. // Segment buffer empty. Shutdown.
st_go_idle(); st_go_idle();
@ -356,7 +364,7 @@ ISR(TIMER1_COMPA_vect)
// Check probing state. // Check probing state.
probe_state_monitor(); if (sys_probe_state == PROBE_ACTIVE) { probe_state_monitor(); }
// Reset step out bits. // Reset step out bits.
st.step_outbits = 0; st.step_outbits = 0;
@ -370,8 +378,8 @@ ISR(TIMER1_COMPA_vect)
if (st.counter_x > st.exec_block->step_event_count) { if (st.counter_x > st.exec_block->step_event_count) {
st.step_outbits |= (1<<X_STEP_BIT); st.step_outbits |= (1<<X_STEP_BIT);
st.counter_x -= st.exec_block->step_event_count; st.counter_x -= st.exec_block->step_event_count;
if (st.exec_block->direction_bits & (1<<X_DIRECTION_BIT)) { sys.position[X_AXIS]--; } if (st.exec_block->direction_bits & (1<<X_DIRECTION_BIT)) { sys_position[X_AXIS]--; }
else { sys.position[X_AXIS]++; } else { sys_position[X_AXIS]++; }
} }
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_y += st.steps[Y_AXIS]; st.counter_y += st.steps[Y_AXIS];
@ -381,8 +389,8 @@ ISR(TIMER1_COMPA_vect)
if (st.counter_y > st.exec_block->step_event_count) { if (st.counter_y > st.exec_block->step_event_count) {
st.step_outbits |= (1<<Y_STEP_BIT); st.step_outbits |= (1<<Y_STEP_BIT);
st.counter_y -= st.exec_block->step_event_count; st.counter_y -= st.exec_block->step_event_count;
if (st.exec_block->direction_bits & (1<<Y_DIRECTION_BIT)) { sys.position[Y_AXIS]--; } if (st.exec_block->direction_bits & (1<<Y_DIRECTION_BIT)) { sys_position[Y_AXIS]--; }
else { sys.position[Y_AXIS]++; } else { sys_position[Y_AXIS]++; }
} }
#ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING #ifdef ADAPTIVE_MULTI_AXIS_STEP_SMOOTHING
st.counter_z += st.steps[Z_AXIS]; st.counter_z += st.steps[Z_AXIS];
@ -392,8 +400,8 @@ ISR(TIMER1_COMPA_vect)
if (st.counter_z > st.exec_block->step_event_count) { if (st.counter_z > st.exec_block->step_event_count) {
st.step_outbits |= (1<<Z_STEP_BIT); st.step_outbits |= (1<<Z_STEP_BIT);
st.counter_z -= st.exec_block->step_event_count; st.counter_z -= st.exec_block->step_event_count;
if (st.exec_block->direction_bits & (1<<Z_DIRECTION_BIT)) { sys.position[Z_AXIS]--; } if (st.exec_block->direction_bits & (1<<Z_DIRECTION_BIT)) { sys_position[Z_AXIS]--; }
else { sys.position[Z_AXIS]++; } else { sys_position[Z_AXIS]++; }
} }
// During a homing cycle, lock out and prevent desired axes from moving. // During a homing cycle, lock out and prevent desired axes from moving.
@ -545,7 +553,6 @@ static uint8_t st_next_block_index(uint8_t block_index)
// 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.
// NOTE: This function does not compile if parking is disabled.
void st_parking_restore_buffer() void st_parking_restore_buffer()
{ {
// Restore step execution data and flags of partially completed block, if necessary. // Restore step execution data and flags of partially completed block, if necessary.
@ -588,36 +595,23 @@ void st_prep_buffer()
// Determine if we need to load a new planner block or if the block needs to be recomputed. // Determine if we need to load a new planner block or if the block needs to be recomputed.
if (pl_block == NULL) { if (pl_block == NULL) {
#ifdef PARKING_ENABLE
// Query planner for a queued block // Query planner for a queued block
if (sys.step_control & STEP_CONTROL_EXECUTE_PARK) { pl_block = plan_get_parking_block(); } if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) { pl_block = plan_get_system_motion_block(); }
else { pl_block = plan_get_current_block(); } else { pl_block = plan_get_current_block(); }
if (pl_block == NULL) { return; } // No planner blocks. Exit. if (pl_block == NULL) { return; } // No planner blocks. Exit.
// Check if we need to only recompute the velocity profile or load a new block. // Check if we need to only recompute the velocity profile or load a new block.
if (prep.recalculate_flag & PREP_FLAG_RECALCULATE) { if (prep.recalculate_flag & PREP_FLAG_RECALCULATE) {
#ifdef PARKING_ENABLE
if (prep.recalculate_flag & PREP_FLAG_PARKING) { prep.recalculate_flag &= ~(PREP_FLAG_RECALCULATE); } if (prep.recalculate_flag & PREP_FLAG_PARKING) { prep.recalculate_flag &= ~(PREP_FLAG_RECALCULATE); }
else { prep.recalculate_flag = false; } else { prep.recalculate_flag = false; }
} else {
#else #else
// Query planner for a queued block
pl_block = plan_get_current_block();
if (pl_block == NULL) { return; } // No planner blocks. Exit.
// Check if we need to only recompute the velocity profile or load a new block.
if (prep.recalculate_flag & PREP_FLAG_RECALCULATE) {
prep.recalculate_flag = false; prep.recalculate_flag = false;
#endif
} else { } else {
#endif
// Load the Bresenham stepping data for the block. // Load the Bresenham stepping data for the block.
prep.st_block_index = st_next_block_index(prep.st_block_index); prep.st_block_index = st_next_block_index(prep.st_block_index);
@ -644,10 +638,11 @@ void st_prep_buffer()
prep.req_mm_increment = REQ_MM_INCREMENT_SCALAR/prep.step_per_mm; prep.req_mm_increment = REQ_MM_INCREMENT_SCALAR/prep.step_per_mm;
prep.dt_remainder = 0.0; // Reset for new segment block prep.dt_remainder = 0.0; // Reset for new segment block
if (sys.step_control & STEP_CONTROL_EXECUTE_HOLD) { if ((sys.step_control & STEP_CONTROL_EXECUTE_HOLD) || (prep.recalculate_flag & PREP_FLAG_DECEL_OVERRIDE)) {
// New block loaded mid-hold. Override planner block entry speed to enforce deceleration. // New block loaded mid-hold. Override planner block entry speed to enforce deceleration.
prep.current_speed = prep.exit_speed; prep.current_speed = prep.exit_speed;
pl_block->entry_speed_sqr = prep.exit_speed*prep.exit_speed; pl_block->entry_speed_sqr = prep.exit_speed*prep.exit_speed;
prep.recalculate_flag &= ~(PREP_FLAG_DECEL_OVERRIDE);
} else { } else {
prep.current_speed = sqrt(pl_block->entry_speed_sqr); prep.current_speed = sqrt(pl_block->entry_speed_sqr);
} }
@ -679,28 +674,53 @@ void st_prep_buffer()
prep.ramp_type = RAMP_ACCEL; // Initialize as acceleration ramp. prep.ramp_type = RAMP_ACCEL; // Initialize as acceleration ramp.
prep.accelerate_until = pl_block->millimeters; prep.accelerate_until = pl_block->millimeters;
#ifdef PARKING_ENABLE float exit_speed_sqr;
if (sys.step_control & STEP_CONTROL_EXECUTE_PARK) { prep.exit_speed = 0.0; } float nominal_speed;
else { prep.exit_speed = plan_get_exec_block_exit_speed(); } if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) {
#else prep.exit_speed = exit_speed_sqr = 0.0; // Enforce stop at end of system motion.
prep.exit_speed = plan_get_exec_block_exit_speed(); } else {
#endif exit_speed_sqr = plan_get_exec_block_exit_speed_sqr();
prep.exit_speed = sqrt(exit_speed_sqr);
}
float exit_speed_sqr = prep.exit_speed*prep.exit_speed; nominal_speed = plan_compute_profile_nominal_speed(pl_block);
float nominal_speed_sqr = nominal_speed*nominal_speed;
float intersect_distance = float intersect_distance =
0.5*(pl_block->millimeters+inv_2_accel*(pl_block->entry_speed_sqr-exit_speed_sqr)); 0.5*(pl_block->millimeters+inv_2_accel*(pl_block->entry_speed_sqr-exit_speed_sqr));
if (intersect_distance > 0.0) {
if (pl_block->entry_speed_sqr > nominal_speed_sqr) { // Only occurs during override reductions.
prep.accelerate_until = pl_block->millimeters - inv_2_accel*(pl_block->entry_speed_sqr-nominal_speed_sqr);
if (prep.accelerate_until <= 0.0) { // Deceleration-only.
prep.ramp_type = RAMP_DECEL;
// prep.decelerate_after = pl_block->millimeters;
// prep.maximum_speed = prep.current_speed;
// Compute override block exit speed since it doesn't match the planner exit speed.
prep.exit_speed = sqrt(pl_block->entry_speed_sqr - 2*pl_block->acceleration*pl_block->millimeters);
prep.recalculate_flag |= PREP_FLAG_DECEL_OVERRIDE; // Flag to load next block as deceleration override.
// TODO: Determine correct handling of parameters in deceleration-only.
// Can be tricky since entry speed will be current speed, as in feed holds.
// Also, look into near-zero speed handling issues with this.
} else {
// Decelerate to cruise or cruise-decelerate types. Guaranteed to intersect updated plan.
prep.decelerate_after = inv_2_accel*(nominal_speed_sqr-exit_speed_sqr);
prep.maximum_speed = nominal_speed;
prep.ramp_type = RAMP_DECEL_OVERRIDE;
}
} else if (intersect_distance > 0.0) {
if (intersect_distance < pl_block->millimeters) { // Either trapezoid or triangle types if (intersect_distance < pl_block->millimeters) { // Either trapezoid or triangle types
// NOTE: For acceleration-cruise and cruise-only types, following calculation will be 0.0. // NOTE: For acceleration-cruise and cruise-only types, following calculation will be 0.0.
prep.decelerate_after = inv_2_accel*(pl_block->nominal_speed_sqr-exit_speed_sqr); prep.decelerate_after = inv_2_accel*(nominal_speed_sqr-exit_speed_sqr);
if (prep.decelerate_after < intersect_distance) { // Trapezoid type if (prep.decelerate_after < intersect_distance) { // Trapezoid type
prep.maximum_speed = sqrt(pl_block->nominal_speed_sqr); prep.maximum_speed = nominal_speed;
if (pl_block->entry_speed_sqr == pl_block->nominal_speed_sqr) { if (pl_block->entry_speed_sqr == nominal_speed_sqr) {
// Cruise-deceleration or cruise-only type. // Cruise-deceleration or cruise-only type.
prep.ramp_type = RAMP_CRUISE; prep.ramp_type = RAMP_CRUISE;
} else { } else {
// Full-trapezoid or acceleration-cruise types // Full-trapezoid or acceleration-cruise types
prep.accelerate_until -= inv_2_accel*(pl_block->nominal_speed_sqr-pl_block->entry_speed_sqr); prep.accelerate_until -= inv_2_accel*(nominal_speed_sqr-pl_block->entry_speed_sqr);
} }
} else { // Triangle type } else { // Triangle type
prep.accelerate_until = intersect_distance; prep.accelerate_until = intersect_distance;
@ -718,6 +738,11 @@ void st_prep_buffer()
prep.maximum_speed = prep.exit_speed; prep.maximum_speed = prep.exit_speed;
} }
} }
#ifdef VARIABLE_SPINDLE
st_prep_block->spindle_pwm = spindle_compute_pwm_value((0.01*sys.spindle_speed_ovr)*pl_block->spindle_speed);
#endif
} }
// Initialize new segment // Initialize new segment
@ -751,6 +776,20 @@ void st_prep_buffer()
do { do {
switch (prep.ramp_type) { switch (prep.ramp_type) {
case RAMP_DECEL_OVERRIDE:
speed_var = pl_block->acceleration*time_var;
mm_var = time_var*(prep.current_speed - 0.5*speed_var);
mm_remaining -= mm_var;
if ((mm_remaining < prep.accelerate_until) || (mm_var <= 0)) {
// Cruise or cruise-deceleration types only for deceleration override.
mm_remaining = prep.accelerate_until; // NOTE: 0.0 at EOB
time_var = 2.0*(pl_block->millimeters-mm_remaining)/(prep.current_speed+prep.maximum_speed);
prep.ramp_type = RAMP_CRUISE;
prep.current_speed = prep.maximum_speed;
} else { // Mid-deceleration override ramp.
prep.current_speed -= speed_var;
}
break;
case RAMP_ACCEL: case RAMP_ACCEL:
// NOTE: Acceleration ramp only computes during first do-while loop. // NOTE: Acceleration ramp only computes during first do-while loop.
speed_var = pl_block->acceleration*time_var; speed_var = pl_block->acceleration*time_var;
@ -908,12 +947,10 @@ void st_prep_buffer()
return; // Bail! return; // Bail!
} else { // End of planner block } else { // End of planner block
// The planner block is complete. All steps are set to be executed in the segment buffer. // The planner block is complete. All steps are set to be executed in the segment buffer.
#ifdef PARKING_ENABLE if (sys.step_control & STEP_CONTROL_EXECUTE_SYS_MOTION) {
if (sys.step_control & STEP_CONTROL_EXECUTE_PARK) {
bit_true(sys.step_control,STEP_CONTROL_END_MOTION); bit_true(sys.step_control,STEP_CONTROL_END_MOTION);
return; return;
} }
#endif
pl_block = NULL; // Set pointer to indicate check and load next planner block. pl_block = NULL; // Set pointer to indicate check and load next planner block.
plan_discard_current_block(); plan_discard_current_block();
} }
@ -927,12 +964,10 @@ void st_prep_buffer()
// however is not exactly the current speed, but the speed computed in the last step segment // however is not exactly the current speed, but the speed computed in the last step segment
// in the segment buffer. It will always be behind by up to the number of segment blocks (-1) // in the segment buffer. It will always be behind by up to the number of segment blocks (-1)
// divided by the ACCELERATION TICKS PER SECOND in seconds. // divided by the ACCELERATION TICKS PER SECOND in seconds.
#ifdef REPORT_REALTIME_RATE float st_get_realtime_rate()
float st_get_realtime_rate() {
{ if (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)){
if (sys.state & (STATE_CYCLE | STATE_HOMING | STATE_HOLD | STATE_MOTION_CANCEL | STATE_SAFETY_DOOR)){
return prep.current_speed; return prep.current_speed;
} }
return 0.0f; return 0.0f;
} }
#endif

View File

@ -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
@ -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

View File

@ -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
@ -123,9 +123,15 @@ uint8_t system_execute_line(char *line)
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(); }
@ -156,26 +162,14 @@ uint8_t system_execute_line(char *line)
// 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]
@ -195,6 +189,7 @@ uint8_t system_execute_line(char *line)
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);
#ifdef ENABLE_BUILD_INFO_WRITE_COMMAND
} else { // Store startup line [IDLE/ALARM] } else { // Store startup line [IDLE/ALARM]
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); } if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
helper_var = char_counter; // Set helper variable as counter to start of user info line. helper_var = char_counter; // Set helper variable as counter to start of user info line.
@ -202,17 +197,24 @@ uint8_t system_execute_line(char *line)
line[char_counter-helper_var] = line[char_counter]; line[char_counter-helper_var] = line[char_counter];
} while (line[char_counter++] != 0); } while (line[char_counter++] != 0);
settings_store_build_info(line); 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') { return(STATUS_INVALID_STATEMENT); }
if (line[++char_counter] != 'T') { return(STATUS_INVALID_STATEMENT); } if (line[3] != 'T') { return(STATUS_INVALID_STATEMENT); }
if (line[++char_counter] != '=') { return(STATUS_INVALID_STATEMENT); } if (line[4] != '=') { return(STATUS_INVALID_STATEMENT); }
if (line[char_counter+2] != 0) { return(STATUS_INVALID_STATEMENT); } if (line[6] != 0) { return(STATUS_INVALID_STATEMENT); }
switch (line[++char_counter]) { switch (line[5]) {
#ifdef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS
case '$': settings_restore(SETTINGS_RESTORE_DEFAULTS); break; case '$': settings_restore(SETTINGS_RESTORE_DEFAULTS); break;
#endif
#ifdef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS
case '#': settings_restore(SETTINGS_RESTORE_PARAMETERS); break; case '#': settings_restore(SETTINGS_RESTORE_PARAMETERS); break;
#endif
#ifdef ENABLE_RESTORE_EEPROM_WIPE_ALL
case '*': settings_restore(SETTINGS_RESTORE_ALL); break; 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);
@ -260,6 +262,16 @@ uint8_t system_execute_line(char *line)
} }
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 +279,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,6 +303,41 @@ 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;
@ -306,10 +353,10 @@ void system_clear_exec_state_flag(uint8_t 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;
} }
@ -319,3 +366,31 @@ void system_clear_exec_alarm_flag(uint8_t mask) {
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;
}

View File

@ -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
@ -36,16 +36,37 @@
#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
// 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 +77,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. [Grbl-Mega Only]
// 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 +88,15 @@
#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 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 +112,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.
int32_t position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
// NOTE: This may need to be a volatile variable, if problems arise.
int32_t probe_position[N_AXIS]; // Last probe position in machine coordinates and steps.
uint8_t probe_succeeded; // Tracks if last probing cycle was successful. uint8_t probe_succeeded; // Tracks if last probing cycle was successful.
uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR. uint8_t homing_axis_lock; // Locks axes when limits engage. Used as an axis motion mask in the stepper ISR.
uint8_t f_override; // Feed rate override value in percent
uint8_t r_override; // Rapids override value in percent
uint8_t spindle_speed_ovr; // Spindle speed value in percent
uint8_t toggle_ovr_mask; // Tracks toggle override states
uint8_t 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;
// NOTE: These position variables may need to be declared as volatiles, if problems arise.
int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
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_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_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_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 +171,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