New jog cancel real-time command. Parser typo fix from last push.
- Added a new jog cancel real-time command. Rather than depending on a feed hold to cancel a jogging motion, this realtime command can be used instead. The main advantage is if a feed hold is used, you can accidentally hold the machine right when Grbl returns to IDLE after completing a jog. And the GUI doesn’t have to worry about tracking this either. - Fixed a typo in the g-code parser edits from the last push. Was causing the G10 set coordinate system command to not work correctly. - Updated the documentation with the jog cancel command.
This commit is contained in:
parent
bf5fc48074
commit
e2e2bb5242
@ -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
|
Date: 2016-09-27
|
||||||
Author: Sonny Jeon
|
Author: Sonny Jeon
|
||||||
|
@ -31,7 +31,7 @@ The main differences are:
|
|||||||
- During a jog, Grbl will report a 'Jog' state while executing the jog.
|
- 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.
|
- 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.
|
- 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.
|
- 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.
|
- 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.
|
- 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.
|
- 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.
|
- 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.
|
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.
|
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.
|
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.
|
||||||
|
|
||||||
|
@ -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.
|
- 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.
|
- 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.
|
- 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.
|
- 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 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.
|
- 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.
|
- 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.
|
- 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.
|
- 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
|
- Feed Overrides
|
||||||
|
|
||||||
- Immediately alters the feed override value. An active feed motion is altered within tens of milliseconds.
|
- 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
|
- `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.
|
- 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.
|
- 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.
|
- While disabled, spindle speed override values may still be altered and will be in effect once the spindle is re-enabled.
|
||||||
|
@ -52,7 +52,6 @@
|
|||||||
#define CMD_STATUS_REPORT '?'
|
#define CMD_STATUS_REPORT '?'
|
||||||
#define CMD_CYCLE_START '~'
|
#define CMD_CYCLE_START '~'
|
||||||
#define CMD_FEED_HOLD '!'
|
#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
|
// 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,
|
// 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_CYCLE_START 0x82
|
||||||
// #define CMD_FEED_HOLD 0x83
|
// #define CMD_FEED_HOLD 0x83
|
||||||
#define CMD_SAFETY_DOOR 0x84
|
#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_RESET 0x90 // Restores feed override value to 100%.
|
||||||
#define CMD_FEED_OVR_COARSE_PLUS 0x91
|
#define CMD_FEED_OVR_COARSE_PLUS 0x91
|
||||||
#define CMD_FEED_OVR_COARSE_MINUS 0x92
|
#define CMD_FEED_OVR_COARSE_MINUS 0x92
|
||||||
|
@ -983,10 +983,10 @@ uint8_t gc_execute_line(char *line)
|
|||||||
// [19. Go to predefined position, Set G10, or Set axis offsets ]:
|
// [19. Go to predefined position, Set G10, or Set axis offsets ]:
|
||||||
switch(gc_block.non_modal_command) {
|
switch(gc_block.non_modal_command) {
|
||||||
case NON_MODAL_SET_COORDINATE_DATA:
|
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.
|
// Update system coordinate system if currently active.
|
||||||
if (gc_state.modal.coord_select == coord_select) {
|
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();
|
system_flag_wco_change();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -23,7 +23,7 @@
|
|||||||
|
|
||||||
// Grbl versioning system
|
// Grbl versioning system
|
||||||
#define GRBL_VERSION "1.1b"
|
#define GRBL_VERSION "1.1b"
|
||||||
#define GRBL_VERSION_BUILD "20160927"
|
#define GRBL_VERSION_BUILD "20160928"
|
||||||
|
|
||||||
// Define standard libraries used by Grbl.
|
// Define standard libraries used by Grbl.
|
||||||
#include <avr/io.h>
|
#include <avr/io.h>
|
||||||
|
@ -276,9 +276,9 @@ void protocol_exec_rt_system()
|
|||||||
// to halt and cancel the remainder of the motion.
|
// to halt and cancel the remainder of the motion.
|
||||||
if (rt_exec & EXEC_MOTION_CANCEL) {
|
if (rt_exec & EXEC_MOTION_CANCEL) {
|
||||||
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
|
// MOTION_CANCEL only occurs during a CYCLE, but a HOLD and SAFETY_DOOR may been initiated beforehand
|
||||||
// to hold the CYCLE. If so, only flag that motion cancel is complete.
|
// to hold the CYCLE. Motion cancel is valid for a single planner block motion only, while jog cancel
|
||||||
// NOTE: State is still STATE_CYCLE.
|
// will handle and clear multiple planner block motions.
|
||||||
sys.suspend |= SUSPEND_MOTION_CANCEL; // Indicate motion cancel when resuming.
|
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.
|
// Execute a feed hold with deceleration, if required. Then, suspend system.
|
||||||
|
120
grbl/report.c
120
grbl/report.c
@ -30,12 +30,10 @@
|
|||||||
|
|
||||||
|
|
||||||
// Internal report utilities to reduce flash with repetitive tasks turned into functions.
|
// 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_line_feed() { printPgmString(PSTR("\r\n")); }
|
||||||
static void report_util_feedback_line_feed() { serial_write(']'); report_util_line_feed(); }
|
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_comment_line_feed() { serial_write(')'); report_util_line_feed(); }
|
||||||
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_axis_values(float *axis_value) {
|
static void report_util_axis_values(float *axis_value) {
|
||||||
uint8_t idx;
|
uint8_t idx;
|
||||||
for (idx=0; idx<N_AXIS; idx++) {
|
for (idx=0; idx<N_AXIS; idx++) {
|
||||||
@ -44,6 +42,66 @@ static void report_util_axis_values(float *axis_value) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// static void report_util_setting_string(uint8_t n) {
|
||||||
|
// serial_write(' ');
|
||||||
|
// serial_write('(');
|
||||||
|
// switch(n) {
|
||||||
|
// case 0: printPgmString(PSTR("stp pulse:us")); break;
|
||||||
|
// case 1: printPgmString(PSTR("idl delay:ms")); break;
|
||||||
|
// case 2: printPgmString(PSTR("stp inv:msk")); break;
|
||||||
|
// case 3: printPgmString(PSTR("dir inv:msk")); break;
|
||||||
|
// case 4: printPgmString(PSTR("stp enbl inv")); break;
|
||||||
|
// case 5: printPgmString(PSTR("lim inv")); break;
|
||||||
|
// case 6: printPgmString(PSTR("prb inv")); break;
|
||||||
|
// case 10: printPgmString(PSTR("rpt:msk")); break;
|
||||||
|
// case 11: printPgmString(PSTR("jnc dev:mm")); break;
|
||||||
|
// case 12: printPgmString(PSTR("arc tol:mm")); break;
|
||||||
|
// case 13: printPgmString(PSTR("rpt inch")); break;
|
||||||
|
// case 20: printPgmString(PSTR("sft lim")); break;
|
||||||
|
// case 21: printPgmString(PSTR("hrd lim")); break;
|
||||||
|
// case 22: printPgmString(PSTR("hm cyc")); break;
|
||||||
|
// case 23: printPgmString(PSTR("hm dir inv:msk")); break;
|
||||||
|
// case 24: printPgmString(PSTR("hm feed:mm/min")); break;
|
||||||
|
// case 25: printPgmString(PSTR("hm seek:mm/min")); break;
|
||||||
|
// case 26: printPgmString(PSTR("hm delay:ms")); break;
|
||||||
|
// case 27: printPgmString(PSTR("hm off:mm")); break;
|
||||||
|
// case 30: printPgmString(PSTR("rpm max")); break;
|
||||||
|
// case 31: printPgmString(PSTR("rpm min")); break;
|
||||||
|
// case 32: printPgmString(PSTR("laser")); break;
|
||||||
|
// default:
|
||||||
|
// n -= AXIS_SETTINGS_START_VAL;
|
||||||
|
// uint8_t idx = 0;
|
||||||
|
// while (n < 10) {
|
||||||
|
// if (n<10) {
|
||||||
|
// print_uint8_base10(n+idx);
|
||||||
|
// switch (idx) {
|
||||||
|
// case 0: printPgmString(PSTR(":stp/mm")); break;
|
||||||
|
// case 1: printPgmString(PSTR(":mm/min")); break;
|
||||||
|
// case 2: printPgmString(PSTR(":mm/s^2")); break;
|
||||||
|
// case 3: printPgmString(PSTR(":mm max")); break;
|
||||||
|
// }
|
||||||
|
// } else {
|
||||||
|
// n -= 10;
|
||||||
|
// idx++;
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
// }
|
||||||
|
// report_util_comment_line_feed();
|
||||||
|
// }
|
||||||
|
|
||||||
|
static void report_util_uint8_setting(uint8_t n, int val) {
|
||||||
|
report_util_setting_prefix(n);
|
||||||
|
print_uint8_base10(val);
|
||||||
|
report_util_line_feed();
|
||||||
|
// report_util_setting_string(n);
|
||||||
|
}
|
||||||
|
static void report_util_float_setting(uint8_t n, float val, uint8_t n_decimal) {
|
||||||
|
report_util_setting_prefix(n);
|
||||||
|
printFloat(val,n_decimal);
|
||||||
|
report_util_line_feed();
|
||||||
|
// report_util_setting_string(n);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
// Handles the primary confirmation protocol response for streaming interfaces and human-feedback.
|
// Handles the primary confirmation protocol response for streaming interfaces and human-feedback.
|
||||||
// For every incoming line, this method responds with an 'ok' for a successful command or an
|
// For every incoming line, this method responds with an 'ok' for a successful command or an
|
||||||
@ -51,8 +109,7 @@ static void report_util_axis_values(float *axis_value) {
|
|||||||
// operation. Errors events can originate from the g-code parser, settings module, or asynchronously
|
// operation. Errors events can originate from the g-code parser, settings module, or asynchronously
|
||||||
// from a critical error, such as a triggered hard limit. Interface should always monitor for these
|
// from a critical error, such as a triggered hard limit. Interface should always monitor for these
|
||||||
// responses.
|
// responses.
|
||||||
// NOTE: In silent mode, all error codes are greater than zero.
|
// NOTE: In REPORT_GUI_MODE, all error codes are greater than zero.
|
||||||
// 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)
|
||||||
{
|
{
|
||||||
switch(status_code) {
|
switch(status_code) {
|
||||||
@ -150,7 +207,6 @@ void report_alarm_message(int8_t alarm_code)
|
|||||||
// messages such as setup warnings, switch toggling, and how to exit alarms.
|
// messages such as setup warnings, switch toggling, and how to exit alarms.
|
||||||
// NOTE: For interfaces, messages are always placed within brackets. And if silent mode
|
// NOTE: For interfaces, messages are always placed within brackets. And if silent mode
|
||||||
// is installed, the message number codes are less than zero.
|
// is installed, the message number codes are less than zero.
|
||||||
// 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("[MSG:"));
|
printPgmString(PSTR("[MSG:"));
|
||||||
@ -224,19 +280,19 @@ void report_grbl_settings() {
|
|||||||
report_util_uint8_setting(5,bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS));
|
report_util_uint8_setting(5,bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS));
|
||||||
report_util_uint8_setting(6,bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN));
|
report_util_uint8_setting(6,bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN));
|
||||||
report_util_uint8_setting(10,settings.status_report_mask);
|
report_util_uint8_setting(10,settings.status_report_mask);
|
||||||
report_util_float_setting(11,settings.junction_deviation);
|
report_util_float_setting(11,settings.junction_deviation,N_DECIMAL_SETTINGVALUE);
|
||||||
report_util_float_setting(12,settings.arc_tolerance);
|
report_util_float_setting(12,settings.arc_tolerance,N_DECIMAL_SETTINGVALUE);
|
||||||
report_util_uint8_setting(13,bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
|
report_util_uint8_setting(13,bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
|
||||||
report_util_uint8_setting(20,bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE));
|
report_util_uint8_setting(20,bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE));
|
||||||
report_util_uint8_setting(21,bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
|
report_util_uint8_setting(21,bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
|
||||||
report_util_uint8_setting(22,bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
|
report_util_uint8_setting(22,bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
|
||||||
report_util_uint8_setting(23,settings.homing_dir_mask);
|
report_util_uint8_setting(23,settings.homing_dir_mask);
|
||||||
report_util_float_setting(24,settings.homing_feed_rate);
|
report_util_float_setting(24,settings.homing_feed_rate,N_DECIMAL_SETTINGVALUE);
|
||||||
report_util_float_setting(25,settings.homing_seek_rate);
|
report_util_float_setting(25,settings.homing_seek_rate,N_DECIMAL_SETTINGVALUE);
|
||||||
report_util_uint8_setting(26,settings.homing_debounce_delay);
|
report_util_uint8_setting(26,settings.homing_debounce_delay);
|
||||||
report_util_float_setting(27,settings.homing_pulloff);
|
report_util_float_setting(27,settings.homing_pulloff,N_DECIMAL_SETTINGVALUE);
|
||||||
report_util_rpm_setting(30,settings.rpm_max);
|
report_util_float_setting(30,settings.rpm_max,N_DECIMAL_RPMVALUE);
|
||||||
report_util_rpm_setting(31,settings.rpm_min);
|
report_util_float_setting(31,settings.rpm_min,N_DECIMAL_RPMVALUE);
|
||||||
#ifdef VARIABLE_SPINDLE
|
#ifdef VARIABLE_SPINDLE
|
||||||
report_util_uint8_setting(32,bit_istrue(settings.flags,BITFLAG_LASER_MODE));
|
report_util_uint8_setting(32,bit_istrue(settings.flags,BITFLAG_LASER_MODE));
|
||||||
#else
|
#else
|
||||||
@ -248,43 +304,15 @@ void report_grbl_settings() {
|
|||||||
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++) {
|
||||||
switch (set_idx) {
|
switch (set_idx) {
|
||||||
case 0: report_util_float_setting(val+idx,settings.steps_per_mm[idx]); break;
|
case 0: report_util_float_setting(val+idx,settings.steps_per_mm[idx],N_DECIMAL_SETTINGVALUE); break;
|
||||||
case 1: report_util_float_setting(val+idx,settings.max_rate[idx]); break;
|
case 1: report_util_float_setting(val+idx,settings.max_rate[idx],N_DECIMAL_SETTINGVALUE); break;
|
||||||
case 2: report_util_float_setting(val+idx,settings.acceleration[idx]/(60*60)); break;
|
case 2: report_util_float_setting(val+idx,settings.acceleration[idx]/(60*60),N_DECIMAL_SETTINGVALUE); break;
|
||||||
case 3: report_util_float_setting(val+idx,-settings.max_travel[idx]); break;
|
case 3: report_util_float_setting(val+idx,-settings.max_travel[idx],N_DECIMAL_SETTINGVALUE); break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
val += AXIS_SETTINGS_INCREMENT;
|
val += AXIS_SETTINGS_INCREMENT;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// printPgmString(PSTR("$0=")); print_uint8_base10(settings.pulse_microseconds);
|
|
||||||
// printPgmString(PSTR("\r\n$1=")); print_uint8_base10(settings.stepper_idle_lock_time);
|
|
||||||
// printPgmString(PSTR("\r\n$2=")); print_uint8_base10(settings.step_invert_mask);
|
|
||||||
// printPgmString(PSTR("\r\n$3=")); print_uint8_base10(settings.dir_invert_mask);
|
|
||||||
// printPgmString(PSTR("\r\n$4=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
|
|
||||||
// printPgmString(PSTR("\r\n$5=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS));
|
|
||||||
// printPgmString(PSTR("\r\n$6=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN));
|
|
||||||
// printPgmString(PSTR("\r\n$10=")); print_uint8_base10(settings.status_report_mask);
|
|
||||||
// printPgmString(PSTR("\r\n$11=")); printFloat_SettingValue(settings.junction_deviation);
|
|
||||||
// printPgmString(PSTR("\r\n$12=")); printFloat_SettingValue(settings.arc_tolerance);
|
|
||||||
// printPgmString(PSTR("\r\n$13=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
|
|
||||||
// printPgmString(PSTR("\r\n$20=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE));
|
|
||||||
// printPgmString(PSTR("\r\n$21=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
|
|
||||||
// printPgmString(PSTR("\r\n$22=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
|
|
||||||
// printPgmString(PSTR("\r\n$23=")); print_uint8_base10(settings.homing_dir_mask);
|
|
||||||
// printPgmString(PSTR("\r\n$24=")); printFloat_SettingValue(settings.homing_feed_rate);
|
|
||||||
// printPgmString(PSTR("\r\n$25=")); printFloat_SettingValue(settings.homing_seek_rate);
|
|
||||||
// printPgmString(PSTR("\r\n$26=")); print_uint8_base10(settings.homing_debounce_delay);
|
|
||||||
// printPgmString(PSTR("\r\n$27=")); printFloat_SettingValue(settings.homing_pulloff);
|
|
||||||
// printPgmString(PSTR("\r\n$30=")); printFloat_RPMValue(settings.rpm_max);
|
|
||||||
// printPgmString(PSTR("\r\n$31=")); printFloat_RPMValue(settings.rpm_min);
|
|
||||||
// #ifdef VARIABLE_SPINDLE
|
|
||||||
// printPgmString(PSTR("\r\n$32=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_LASER_MODE));
|
|
||||||
// printPgmString(PSTR("\r\n"));
|
|
||||||
// #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);
|
||||||
|
@ -157,6 +157,11 @@ ISR(SERIAL_RX)
|
|||||||
if (data > 0x7F) { // Real-time control characters are extended ACSII only.
|
if (data > 0x7F) { // Real-time control characters are extended ACSII only.
|
||||||
switch(data) {
|
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_JOG_CANCEL:
|
||||||
|
if (sys.state & STATE_JOG) { // Block all other states from invoking motion cancel.
|
||||||
|
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
|
||||||
|
}
|
||||||
|
break;
|
||||||
#ifdef DEBUG
|
#ifdef DEBUG
|
||||||
case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug,EXEC_DEBUG_REPORT); SREG = sreg;} break;
|
case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug,EXEC_DEBUG_REPORT); SREG = sreg;} break;
|
||||||
#endif
|
#endif
|
||||||
|
@ -202,10 +202,7 @@ uint8_t system_execute_line(char *line)
|
|||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 'R' : // Restore defaults [IDLE/ALARM]
|
case 'R' : // Restore defaults [IDLE/ALARM]
|
||||||
if (line[2] != 'S') { return(STATUS_INVALID_STATEMENT); }
|
if ((line[2] != 'S') || (line[3] != 'T') || (line[4] != '=') || (line[6] != 0)) { return(STATUS_INVALID_STATEMENT); }
|
||||||
if (line[3] != 'T') { return(STATUS_INVALID_STATEMENT); }
|
|
||||||
if (line[4] != '=') { return(STATUS_INVALID_STATEMENT); }
|
|
||||||
if (line[6] != 0) { return(STATUS_INVALID_STATEMENT); }
|
|
||||||
switch (line[5]) {
|
switch (line[5]) {
|
||||||
#ifdef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS
|
#ifdef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS
|
||||||
case '$': settings_restore(SETTINGS_RESTORE_DEFAULTS); break;
|
case '$': settings_restore(SETTINGS_RESTORE_DEFAULTS); break;
|
||||||
|
Loading…
Reference in New Issue
Block a user