New EEPROM restore functions.

- Tweaked the previous EEPROM restore implementation and added new
functionality.

- `$RST=$` restores the `$$` grbl settings back to firmware defaults,
which are set when compiled.

- `$RST=#` restores the `$#` parameters in EEPROM. At times it’s useful
to clear these and start over, rather than manually writing each entry.

-`$RST=*` wipe all of the data in EEPROM that Grbl uses and restores
them to defaults. This includes `$$` settings, `$#` parameters, `$N`
startup lines, and `$i` build info string.

NOTE: This doesn’t write zeros throughout the EEPROM. It only writes
where Grbl looks for data. For a complete wipe, please use the Arduino
IDE’s EEPROM clear example.

- Refactored the restore and wipe functions in settings.c to
accommodate the new commands.
This commit is contained in:
Sonny Jeon
2015-06-20 10:27:24 -06:00
parent e6db564511
commit 81505e6a81
6 changed files with 90 additions and 83 deletions

View File

@ -204,9 +204,16 @@ uint8_t system_execute_line(char *line)
case 'R' : // Restore defaults [IDLE/ALARM]
if (line[++char_counter] != 'S') { return(STATUS_INVALID_STATEMENT); }
if (line[++char_counter] != 'T') { return(STATUS_INVALID_STATEMENT); }
if (line[++char_counter] != 0) { return(STATUS_INVALID_STATEMENT); }
if (line[++char_counter] != '=') { return(STATUS_INVALID_STATEMENT); }
if (line[char_counter+2] != 0) { return(STATUS_INVALID_STATEMENT); }
switch (line[++char_counter]) {
case '$': settings_restore(SETTINGS_RESTORE_DEFAULTS); break;
case '#': settings_restore(SETTINGS_RESTORE_PARAMETERS); break;
case '*': settings_restore(SETTINGS_RESTORE_ALL); break;
default: return(STATUS_INVALID_STATEMENT);
}
report_feedback_message(MESSAGE_RESTORE_DEFAULTS);
settings_restore_global_settings();
mc_reset(); // Force reset to ensure settings are initialized correctly.
break;
case 'N' : // Startup lines. [IDLE/ALARM]
if ( line[++char_counter] == 0 ) { // Print startup lines