Browse Source

Merge pull request #9056 from thinkyhead/bf2_new_eeprom_powers

[2.0.x] New EEPROM powers
pull/1/head
Scott Lahteine 7 years ago
committed by GitHub
parent
commit
013c911a82
No known key found for this signature in database GPG Key ID: 4AEE18F83AFDEB23
  1. 4
      Marlin/src/HAL/HAL_AVR/persistent_store_impl.cpp
  2. 4
      Marlin/src/HAL/HAL_DUE/persistent_store_impl.cpp
  3. 11
      Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp
  4. 8
      Marlin/src/HAL/HAL_STM32F1/persistent_store_flash.cpp
  5. 8
      Marlin/src/HAL/HAL_STM32F1/persistent_store_impl.cpp
  6. 4
      Marlin/src/HAL/HAL_TEENSY35_36/persistent_store_impl.cpp
  7. 2
      Marlin/src/HAL/persistent_store_api.h
  8. 12
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  9. 12
      Marlin/src/gcode/eeprom/M500-M504.cpp
  10. 3
      Marlin/src/gcode/gcode.cpp
  11. 5
      Marlin/src/gcode/gcode.h
  12. 1
      Marlin/src/lcd/ultralcd.cpp
  13. 647
      Marlin/src/module/configuration_store.cpp
  14. 26
      Marlin/src/module/configuration_store.h

4
Marlin/src/HAL/HAL_AVR/persistent_store_impl.cpp

@ -38,10 +38,10 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
return false;
}
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
uint8_t c = eeprom_read_byte((unsigned char*)pos);
*value = c;
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;

4
Marlin/src/HAL/HAL_DUE/persistent_store_impl.cpp

@ -43,10 +43,10 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
return false;
}
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
uint8_t c = eeprom_read_byte((unsigned char*)pos);
*value = c;
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;

11
Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp

@ -128,7 +128,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
return (bytes_written != size); // return true for any error
}
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
UINT bytes_read = 0;
FRESULT s;
s = f_lseek(&eeprom_file, pos);
@ -140,7 +140,15 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
SERIAL_PROTOCOLLNPAIR(" f_lseek()=", (int)s);
return true;
}
if (writing) {
s = f_read(&eeprom_file, (void *)value, size, &bytes_read);
crc16(crc, value, size);
}
else {
uint8_t temp[size];
s = f_read(&eeprom_file, (void *)temp, size, &bytes_read);
crc16(crc, temp, size);
}
if (s) {
SERIAL_PROTOCOLPAIR(" read_data(", pos); // This extra chit-chat goes away soon. But it is helpful
SERIAL_PROTOCOLPAIR(",", (int)value); // right now to see errors that are happening in the
@ -151,7 +159,6 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
SERIAL_PROTOCOLLNPAIR("\n bytes_read=", bytes_read);
return true;
}
crc16(crc, value, size);
pos = pos + size;
return bytes_read != size; // return true for any error
}

8
Marlin/src/HAL/HAL_STM32F1/persistent_store_flash.cpp

@ -93,13 +93,13 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
return true;
}
void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
void read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
for (uint16_t i = 0; i < size; i++) {
byte* accessPoint = (byte*)(pageBase + pos + i);
value[i] = *accessPoint;
uint8_t c = *accessPoint;
if (writing) value[i] = c;
crc16(crc, &c, 1);
}
crc16(crc, value, size);
pos += ((size + 1) & ~1);
}

8
Marlin/src/HAL/HAL_STM32F1/persistent_store_impl.cpp

@ -62,7 +62,6 @@ bool access_start() {
return true;
}
bool access_finish(){
if (!card.cardOK) return false;
int16_t bytes_written = 0;
@ -81,11 +80,12 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
return false;
}
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
for (int i = 0; i < size; i++) {
value[i] = HAL_STM32F1_eeprom_content [pos + i];
uint8_t c = HAL_STM32F1_eeprom_content[pos + i];
if (writing) value[i] = c`;
crc16(crc, &c, 1);
}
crc16(crc, value, size);
pos += size;
return false;
}

4
Marlin/src/HAL/HAL_TEENSY35_36/persistent_store_impl.cpp

@ -38,10 +38,10 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
return false;
}
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
uint8_t c = eeprom_read_byte((unsigned char*)pos);
*value = c;
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;

2
Marlin/src/HAL/persistent_store_api.h

@ -10,7 +10,7 @@ namespace PersistentStore {
bool access_start();
bool access_finish();
bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc);
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc);
bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing=true);
} // PersistentStore
} // HAL

12
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp

@ -309,12 +309,6 @@
void unified_bed_leveling::G29() {
if (!settings.calc_num_meshes()) {
SERIAL_PROTOCOLLNPGM("?Enable EEPROM and init with");
SERIAL_PROTOCOLLNPGM("M502, M500, M501 in that order.\n");
return;
}
if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem,
// Check for commands that require the printer to be homed
@ -1272,8 +1266,8 @@
SERIAL_EOL();
safe_delay(50);
SERIAL_PROTOCOLPAIR("Meshes go from ", hex_address((void*)settings.get_start_of_meshes()));
SERIAL_PROTOCOLLNPAIR(" to ", hex_address((void*)settings.get_end_of_meshes()));
SERIAL_PROTOCOLPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()));
SERIAL_PROTOCOLLNPAIR(" to ", hex_address((void*)settings.meshes_end_index()));
safe_delay(50);
SERIAL_PROTOCOLLNPAIR("sizeof(ubl) : ", (int)sizeof(ubl));
@ -1282,7 +1276,7 @@
SERIAL_EOL();
safe_delay(25);
SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.get_end_of_meshes() - settings.get_start_of_meshes())));
SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index())));
safe_delay(50);
SERIAL_PROTOCOLPAIR("EEPROM can hold ", settings.calc_num_meshes());

12
Marlin/src/gcode/eeprom/M500-M503.cpp → Marlin/src/gcode/eeprom/M500-M504.cpp

@ -55,3 +55,15 @@ void GcodeSuite::M502() {
}
#endif // !DISABLE_M503
#if ENABLED(EEPROM_SETTINGS)
/**
* M504: Validate EEPROM Contents
*/
void GcodeSuite::M504() {
if (settings.validate()) {
SERIAL_ECHO_START();
SERIAL_ECHOLNPGM("EEPROM OK");
}
}
#endif

3
Marlin/src/gcode/gcode.cpp

@ -610,6 +610,9 @@ void GcodeSuite::process_parsed_command() {
#if DISABLED(DISABLE_M503)
case 503: M503(); break; // M503: print settings currently in memory
#endif
#if ENABLED(EEPROM_SETTINGS)
case 504: M504(); break; // M504: Validate EEPROM contents
#endif
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
case 540: M540(); break; // M540: Set abort on endstop hit for SD printing

5
Marlin/src/gcode/gcode.h

@ -271,8 +271,8 @@ public:
static WorkspacePlane workspace_plane;
#endif
#if ENABLED(CNC_COORDINATE_SYSTEMS)
#define MAX_COORDINATE_SYSTEMS 9
#if ENABLED(CNC_COORDINATE_SYSTEMS)
static int8_t active_coordinate_system;
static float coordinate_system[MAX_COORDINATE_SYSTEMS][XYZ];
static bool select_coordinate_system(const int8_t _new);
@ -681,6 +681,9 @@ private:
#if DISABLED(DISABLE_M503)
static void M503();
#endif
#if ENABLED(EEPROM_SETTINGS)
static void M504();
#endif
#if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
static void M540();

1
Marlin/src/lcd/ultralcd.cpp

@ -2309,7 +2309,6 @@ void kill_screen(const char* lcd_msg) {
MENU_BACK(MSG_UBL_LEVEL_BED);
if (!WITHIN(ubl_storage_slot, 0, a - 1)) {
STATIC_ITEM(MSG_NO_STORAGE);
STATIC_ITEM(MSG_INIT_EEPROM);
}
else {
MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, a - 1);

647
Marlin/src/module/configuration_store.cpp

File diff suppressed because it is too large

26
Marlin/src/module/configuration_store.h

@ -29,31 +29,31 @@ class MarlinSettings {
public:
MarlinSettings() { }
static uint16_t datasize();
static void reset();
static bool save();
static bool save(); // Return 'true' if data was saved
FORCE_INLINE static bool init_eeprom() {
bool success = true;
reset();
#if ENABLED(EEPROM_SETTINGS)
if ((success = save())) {
#if ENABLED(AUTO_BED_LEVELING_UBL)
success = load(); // UBL uses load() to know the end of EEPROM
#elif ENABLED(EEPROM_CHITCHAT)
report();
success = save();
#if ENABLED(EEPROM_CHITCHAT)
if (success) report();
#endif
}
#endif
return success;
}
#if ENABLED(EEPROM_SETTINGS)
static bool load();
static bool load(); // Return 'true' if data was loaded ok
static bool validate(); // Return 'true' if EEPROM data is ok
#if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system
// That can store is enabled
FORCE_INLINE static int16_t get_start_of_meshes() { return meshes_begin; }
FORCE_INLINE static int16_t get_end_of_meshes() { return meshes_end; }
static int16_t meshes_start_index();
FORCE_INLINE static int16_t meshes_end_index() { return meshes_end; }
static uint16_t calc_num_meshes();
static void store_mesh(const int8_t slot);
static void load_mesh(const int8_t slot, void * const into=NULL);
@ -77,16 +77,18 @@ class MarlinSettings {
static void postprocess();
#if ENABLED(EEPROM_SETTINGS)
static bool eeprom_error;
static bool eeprom_error, validating;
#if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system
// That can store is enabled
static int16_t meshes_begin;
const static int16_t meshes_end = E2END - 128; // 128 is a placeholder for the size of the MAT; the MAT will always
// live at the very end of the eeprom
#endif
static bool _load();
static bool size_error(const uint16_t size);
#endif
};

Loading…
Cancel
Save