diff --git a/doc/log/commit_log_v1.1.txt b/doc/log/commit_log_v1.1.txt index da365fc..dde1665 100644 --- a/doc/log/commit_log_v1.1.txt +++ b/doc/log/commit_log_v1.1.txt @@ -1,3 +1,18 @@ +---------------- +Date: 2016-09-27 +Author: Sonny Jeon +Subject: Refactored g-code parser. Saved 60bytes flash and some ram. Edited Readme. + +- Freed up another 60 bytes of flash and 12-24 bytes of stack RAM by +using the pre-allocated IJK arc offset vector that is guaranteed to be +not in use. Only G10 and G28/30 require fetching from EEPROM and +retaining extra data. Both commands use axis words, which rules out +G2/3 arcs using IJK offsets existing in same block. Not ideal, but +every byte helps. + +- Edited README. + + ---------------- Date: 2016-09-27 Author: Sonny Jeon diff --git a/doc/markdown/jogging.md b/doc/markdown/jogging.md index b9f4921..98fff6a 100644 --- a/doc/markdown/jogging.md +++ b/doc/markdown/jogging.md @@ -31,7 +31,7 @@ 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. +- All jogging motion(s) may be cancelled at anytime with a simple jog cancel realtime command or a feed hold or safety door event. Grbl will automatically flush Grbl's internal buffers of any queued jogging motions and return to the 'Idle' state. No soft-reset required. - If soft-limits are enabled, jog commands that exceed the machine travel simply does not execute the command and return an error, rather than throwing an alarm in normal operation. - IMPORTANT: Jogging does not alter the g-code parser state. Hence, no g-code modes need to be explicitly managed, unlike previous ways of implementing jogs with commands like 'G91G1X1F100'. Since G91, G1, and F feed rates are modal and if they are not changed back prior to resuming/starting a job, a job may not run how its was intended and result in a crash. @@ -48,14 +48,14 @@ With a combination of the new jog cancel and moving in `G91` incremental mode, t - Send Grbl a very short `G91` incremental distance jog command with a feed rate based on the joystick throw. - Wait for an 'ok' acknowledgement before restarting the loop. - Continually read the joystick input and send Grbl short jog motions to keep Grbl's planner buffer full. - - If the joystick is returned to its neutral position, stop the jog loop and simply send Grbl a jog cancel (or feed hold) real-time command. This will stop motion immediately somewhere along the programmed jog path with virtually zero-latency and automatically flush Grbl's planner queue. + - If the joystick is returned to its neutral position, stop the jog loop and simply send Grbl a jog cancel real-time command. This will stop motion immediately somewhere along the programmed jog path with virtually zero-latency and automatically flush Grbl's planner queue. It's not advised to use a feed hold to cancel a jog, as it can lead to inadvertently suspending Grbl if its sent after returning to the IDLE state. The overall idea is to minimize the total distance in the planner queue to provide a low-latency feel to joystick control. The main trick is ensuring there is just enough distance in the planner queue, such that the programmed feed rate is always met. How to compute this will be explain later. In practice, most machines will have a 0.5-1.0 second latency. When combined with the immediate jog cancel command, joystick interaction can be quite enjoyable and satisfying. However, please note, if a machine has a low acceleration and is being asked to move at a high programmed feed rate, joystick latency can get up to a handful of seconds. It may sound bad, but this is how long it'll take for a low acceleration machine, traveling at a high feed rate, to slow down to a stop. The argument can be made for a low acceleration machine that you really shouldn't be jogging at a high feed rate. It is difficult for a user to gauge where the machine will come to a stop. You risk overshooting your target destination, which can result in an expensive or dangerous crash. -One of the advantages of this approach is that a GUI can deterministically track where Grbl will go by the jog commands it has already sent to Grbl. As long as a feed hold doesn't cancel the jog state, every jog command is guaranteed to execute. In the event a feed hold is sent, the GUI would just need to refresh their internal position from a status report after Grbl has cleared planner buffer and returned to the IDLE state from the JOG state. This stopped position will always be somewhere along the programmed jog path. If desired, jogging can then be quickly and easily restarted with a new tracked path. +One of the advantages of this approach is that a GUI can deterministically track where Grbl will go by the jog commands it has already sent to Grbl. As long as a jog isn't cancelled, every jog command is guaranteed to execute. In the event a jog cancel is invoked, the GUI would just need to refresh their internal position from a status report after Grbl has cleared planner buffer and returned to the IDLE (or DOOR, if ajar) state from the JOG state. This stopped position will always be somewhere along the programmed jog path. If desired, jogging can then be quickly and easily restarted with a new tracked path. In combination with `G53` move in machine coordinates, a GUI can restrict jogging from moving into "keep-out" zones inside the machine space. This can be very useful for avoiding crashing into delicate probing hardware, workholding mechanisms, or other fixed features inside machine space that you want to avoid. diff --git a/doc/markdown/realtime_cmds.md b/doc/markdown/realtime_cmds.md index 42bb04d..4edc3d7 100644 --- a/doc/markdown/realtime_cmds.md +++ b/doc/markdown/realtime_cmds.md @@ -50,6 +50,7 @@ The normal ASCII realtime command characters used in Grbl v0.9 have been retaine - Places Grbl into a suspend or HOLD state. If in motion, the machine will decelerate to a stop and then be suspended. - Command executes when Grbl is in an IDLE, RUN, or JOG state. It is otherwise ignored. + - If jogging, a feed hold will cancel the jog motion and flush all remaining jog motions in the planner buffer. The state will return from JOG to IDLE or DOOR, if was detected as ajar during the active hold. - By machine control definition, a feed hold does not disable the spindle or coolant. Only motion. - An input pin is available to connect a button or switch. @@ -66,10 +67,18 @@ Grbl v1.1 installed more than a dozen new realtime commands to control feed, rap - If already in a suspend state or HOLD, the DOOR state supersedes it. - If the parking compile-time option is enabled, Grbl will park the spindle to a specified location. - Command executes when Grbl is in an IDLE, HOLD, RUN, HOMING, or JOG state. It is otherwise ignored. + - If jogging, a safety door will cancel the jog and all queued motions in the planner buffer. When the safety door is closed and resumed, Grbl will return to an IDLE state. - An input pin is available to connect a button or switch, if enabled with a compile-time option. - Some builds of Grbl v0.9 used the `@` character for this command, but it was undocumented. Moved to extended-ASCII to prevent accidental commanding. +- `0x85` : Jog Cancel + + - Immediately cancels the current jog state by a feed hold and automatically flushing any remaining jog commands in the buffer. + - Command is ignored, if not in a JOG state or if jog cancel is already invoked and in-process. + - Grbl will return to the IDLE state or the DOOR state, if the safety door was detected as ajar during the cancel. + + - Feed Overrides - Immediately alters the feed override value. An active feed motion is altered within tens of milliseconds. @@ -114,7 +123,7 @@ Grbl v1.1 installed more than a dozen new realtime commands to control feed, rap - `0x9E` : Toggle Spindle Stop - - Toggles spindle enable or disable state immediately, but only while in the HOLD. + - Toggles spindle enable or disable state immediately, but only while in the HOLD state. - The command is otherwise ignored, especially while in motion. This prevents accidental disabling during a job that can either destroy the part/machine or 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. diff --git a/grbl/config.h b/grbl/config.h index 4bd860d..6acee3a 100644 --- a/grbl/config.h +++ b/grbl/config.h @@ -52,7 +52,6 @@ #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, @@ -63,7 +62,8 @@ // #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_JOG_CANCEL 0x85 +#define CMD_DEBUG_REPORT 0x86 // Only when DEBUG enabled, sends debug report in '{}' braces. #define CMD_FEED_OVR_RESET 0x90 // Restores feed override value to 100%. #define CMD_FEED_OVR_COARSE_PLUS 0x91 #define CMD_FEED_OVR_COARSE_MINUS 0x92 diff --git a/grbl/gcode.c b/grbl/gcode.c index 4969bc5..16a5bec 100644 --- a/grbl/gcode.c +++ b/grbl/gcode.c @@ -983,10 +983,10 @@ uint8_t gc_execute_line(char *line) // [19. Go to predefined position, Set G10, or Set axis offsets ]: switch(gc_block.non_modal_command) { case NON_MODAL_SET_COORDINATE_DATA: - settings_write_coord_data(coord_select,gc_block.values.xyz); + settings_write_coord_data(coord_select,gc_block.values.ijk); // Update system coordinate system if currently active. if (gc_state.modal.coord_select == coord_select) { - memcpy(gc_state.coord_system,gc_block.values.xyz,N_AXIS*sizeof(float)); + memcpy(gc_state.coord_system,gc_block.values.ijk,N_AXIS*sizeof(float)); system_flag_wco_change(); } break; diff --git a/grbl/grbl.h b/grbl/grbl.h index 0e05310..ac5d6c5 100644 --- a/grbl/grbl.h +++ b/grbl/grbl.h @@ -23,7 +23,7 @@ // Grbl versioning system #define GRBL_VERSION "1.1b" -#define GRBL_VERSION_BUILD "20160927" +#define GRBL_VERSION_BUILD "20160928" // Define standard libraries used by Grbl. #include diff --git a/grbl/protocol.c b/grbl/protocol.c index e167769..a09a6a7 100644 --- a/grbl/protocol.c +++ b/grbl/protocol.c @@ -276,9 +276,9 @@ void protocol_exec_rt_system() // to halt and cancel the remainder of the motion. if (rt_exec & EXEC_MOTION_CANCEL) { // MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand - // to hold the CYCLE. If so, only flag that motion cancel is complete. - // NOTE: State is still STATE_CYCLE. - sys.suspend |= SUSPEND_MOTION_CANCEL; // Indicate motion cancel when resuming. + // to hold the CYCLE. Motion cancel is valid for a single planner block motion only, while jog cancel + // will handle and clear multiple planner block motions. + if (!(sys.state & STATE_JOG)) { sys.suspend |= SUSPEND_MOTION_CANCEL; } // NOTE: State is STATE_CYCLE. } // Execute a feed hold with deceleration, if required. Then, suspend system. diff --git a/grbl/report.c b/grbl/report.c index 70e780a..4e924ab 100644 --- a/grbl/report.c +++ b/grbl/report.c @@ -30,12 +30,10 @@ // Internal report utilities to reduce flash with repetitive tasks turned into functions. +void report_util_setting_prefix(uint8_t n) { serial_write('$'); print_uint8_base10(n); serial_write('='); } static void report_util_line_feed() { printPgmString(PSTR("\r\n")); } static void report_util_feedback_line_feed() { serial_write(']'); report_util_line_feed(); } -void report_util_setting_prefix(uint8_t n) { serial_write('$'); print_uint8_base10(n); serial_write('='); } -static void report_util_uint8_setting(uint8_t n, int val) { report_util_setting_prefix(n); print_uint8_base10(val); report_util_line_feed(); } -static void report_util_float_setting(uint8_t n, float val) { report_util_setting_prefix(n); printFloat(val,N_DECIMAL_SETTINGVALUE); report_util_line_feed(); } -static void report_util_rpm_setting(uint8_t n, float val) { report_util_setting_prefix(n); printFloat(val,N_DECIMAL_RPMVALUE); report_util_line_feed(); } +// static void report_util_comment_line_feed() { serial_write(')'); report_util_line_feed(); } static void report_util_axis_values(float *axis_value) { uint8_t idx; for (idx=0; idx