Ver código fonte

Update PersistentStore api (#11538)

- Clean up the API to use a `static` class instance to adhere to Marlin convention
- Add `const` position data access for read/write
- Add Storage capacity to the interface
Chris Pepper 5 anos atrás
pai
commit
66d2b48b59

Marlin/src/HAL/HAL_AVR/persistent_store_impl.cpp → Marlin/src/HAL/HAL_AVR/persistent_store_eeprom.cpp Ver arquivo

@@ -1,18 +1,15 @@
1 1
 #ifdef __AVR__
2 2
 
3
-#include "../persistent_store_api.h"
4
-
5 3
 #include "../../inc/MarlinConfig.h"
6 4
 
7 5
 #if ENABLED(EEPROM_SETTINGS)
8 6
 
9
-namespace HAL {
10
-namespace PersistentStore {
7
+#include "../persistent_store_api.h"
11 8
 
12
-bool access_start() { return true; }
13
-bool access_finish() { return true; }
9
+bool PersistentStore::access_start() { return true; }
10
+bool PersistentStore::access_finish() { return true; }
14 11
 
15
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
12
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
16 13
   while (size--) {
17 14
     uint8_t * const p = (uint8_t * const)pos;
18 15
     uint8_t v = *value;
@@ -33,7 +30,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
33 30
   return false;
34 31
 }
35 32
 
36
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
33
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
37 34
   do {
38 35
     uint8_t c = eeprom_read_byte((unsigned char*)pos);
39 36
     if (writing) *value = c;
@@ -44,7 +41,20 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const boo
44 41
   return false;  // always assume success for AVR's
45 42
 }
46 43
 
44
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
45
+  int data_pos = pos;
46
+  uint16_t crc = 0;
47
+  return write_data(data_pos, value, size, &crc);
47 48
 }
49
+
50
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
51
+  int data_pos = pos;
52
+  uint16_t crc = 0;
53
+  return read_data(data_pos, value, size, &crc);
54
+}
55
+
56
+const size_t PersistentStore::capacity() {
57
+  return E2END + 1;
48 58
 }
49 59
 
50 60
 #endif // EEPROM_SETTINGS

Marlin/src/HAL/HAL_DUE/persistent_store_impl.cpp → Marlin/src/HAL/HAL_DUE/persistent_store_eeprom.cpp Ver arquivo

@@ -8,19 +8,16 @@
8 8
 
9 9
 extern void eeprom_flush(void);
10 10
 
11
-namespace HAL {
12
-namespace PersistentStore {
11
+bool PersistentStore::access_start() { return true; }
13 12
 
14
-bool access_start() { return true; }
15
-
16
-bool access_finish() {
13
+bool PersistentStore::access_finish() {
17 14
   #if DISABLED(I2C_EEPROM) && DISABLED(SPI_EEPROM)
18 15
     eeprom_flush();
19 16
   #endif
20 17
   return true;
21 18
 }
22 19
 
23
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
20
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
24 21
   while (size--) {
25 22
     uint8_t * const p = (uint8_t * const)pos;
26 23
     uint8_t v = *value;
@@ -41,7 +38,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
41 38
   return false;
42 39
 }
43 40
 
44
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
41
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
45 42
   do {
46 43
     uint8_t c = eeprom_read_byte((unsigned char*)pos);
47 44
     if (writing) *value = c;
@@ -52,8 +49,21 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const boo
52 49
   return false;
53 50
 }
54 51
 
52
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
53
+  int data_pos = pos;
54
+  uint16_t crc = 0;
55
+  return write_data(data_pos, value, size, &crc);
56
+}
57
+
58
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
59
+  int data_pos = pos;
60
+  uint16_t crc = 0;
61
+  return read_data(data_pos, value, size, &crc);
55 62
 }
63
+
64
+const size_t PersistentStore::capacity() {
65
+  return E2END + 1;
56 66
 }
57 67
 
58 68
 #endif // EEPROM_SETTINGS
59
-#endif // __AVR__
69
+#endif // ARDUINO_ARCH_SAM

+ 0
- 2
Marlin/src/HAL/HAL_LPC1768/include/Arduino.h Ver arquivo

@@ -43,8 +43,6 @@
43 43
 #define FALLING      0x03
44 44
 #define RISING       0x04
45 45
 
46
-#define E2END 0xFFF // EEPROM end address
47
-
48 46
 typedef uint8_t byte;
49 47
 #define PROGMEM
50 48
 #define PSTR(v) (v)

Marlin/src/HAL/HAL_LPC1768/persistent_store_impl.cpp → Marlin/src/HAL/HAL_LPC1768/persistent_store_sdcard.cpp Ver arquivo

@@ -27,19 +27,17 @@
27 27
 
28 28
 #include "../persistent_store_api.h"
29 29
 
30
-#include "chanfs/diskio.h"
31
-#include "chanfs/ff.h"
30
+#include <chanfs/diskio.h>
31
+#include <chanfs/ff.h>
32 32
 
33 33
 extern uint32_t MSC_Aquire_Lock();
34 34
 extern uint32_t MSC_Release_Lock();
35 35
 
36
-namespace HAL {
37
-namespace PersistentStore {
38
-
39 36
 FATFS fat_fs;
40 37
 FIL eeprom_file;
38
+bool eeprom_file_open = false;
41 39
 
42
-bool access_start() {
40
+bool PersistentStore::access_start() {
43 41
   const char eeprom_erase_value = 0xFF;
44 42
   MSC_Aquire_Lock();
45 43
   if (f_mount(&fat_fs, "", 1)) {
@@ -53,7 +51,7 @@ bool access_start() {
53 51
     UINT bytes_written;
54 52
     FSIZE_t file_size = f_size(&eeprom_file);
55 53
     f_lseek(&eeprom_file, file_size);
56
-    while (file_size <= E2END && res == FR_OK) {
54
+    while (file_size < capacity() && res == FR_OK) {
57 55
       res = f_write(&eeprom_file, &eeprom_erase_value, 1, &bytes_written);
58 56
       file_size++;
59 57
     }
@@ -61,14 +59,16 @@ bool access_start() {
61 59
   if (res == FR_OK) {
62 60
     f_lseek(&eeprom_file, 0);
63 61
     f_sync(&eeprom_file);
62
+    eeprom_file_open = true;
64 63
   }
65 64
   return res == FR_OK;
66 65
 }
67 66
 
68
-bool access_finish() {
67
+bool PersistentStore::access_finish() {
69 68
   f_close(&eeprom_file);
70 69
   f_unmount("");
71 70
   MSC_Release_Lock();
71
+  eeprom_file_open = false;
72 72
   return true;
73 73
 }
74 74
 
@@ -98,7 +98,8 @@ bool access_finish() {
98 98
 //    FR_INVALID_PARAMETER     /* (19) Given parameter is invalid */
99 99
 //  } FRESULT;
100 100
 
101
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
101
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
102
+  if(!eeprom_file_open) return true;
102 103
   FRESULT s;
103 104
   UINT bytes_written = 0;
104 105
 
@@ -128,7 +129,8 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
128 129
   return (bytes_written != size);  // return true for any error
129 130
 }
130 131
 
131
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
132
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
133
+  if(!eeprom_file_open) return true;
132 134
   UINT bytes_read = 0;
133 135
   FRESULT s;
134 136
   s = f_lseek(&eeprom_file, pos);
@@ -163,8 +165,21 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const boo
163 165
   return bytes_read != size;  // return true for any error
164 166
 }
165 167
 
166
-} // PersistentStore
167
-} // HAL
168
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
169
+  int data_pos = pos;
170
+  uint16_t crc = 0;
171
+  return write_data(data_pos, value, size, &crc);
172
+}
173
+
174
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
175
+  int data_pos = pos;
176
+  uint16_t crc = 0;
177
+  return read_data(data_pos, value, size, &crc);
178
+}
179
+
180
+const size_t PersistentStore::capacity() {
181
+  return 4096; //4KiB of Emulated EEPROM
182
+}
168 183
 
169 184
 #endif // EEPROM_SETTINGS
170 185
 #endif // TARGET_LPC1768

+ 24
- 15
Marlin/src/HAL/HAL_STM32F1/persistent_store_flash.cpp Ver arquivo

@@ -39,28 +39,23 @@
39 39
 #include <flash_stm32.h>
40 40
 #include <EEPROM.h>
41 41
 
42
-namespace HAL {
43
-namespace PersistentStore {
44
-
45
-namespace {
46
-  // Store settings in the last two pages
47
-  // Flash pages must be erased before writing, so keep track.
48
-  bool firstWrite = false;
49
-  uint32_t pageBase = EEPROM_START_ADDRESS;
50
-}
42
+// Store settings in the last two pages
43
+// Flash pages must be erased before writing, so keep track.
44
+bool firstWrite = false;
45
+uint32_t pageBase = EEPROM_START_ADDRESS;
51 46
 
52
-bool access_start() {
47
+bool PersistentStore::access_start() {
53 48
   firstWrite = true;
54 49
   return true;
55 50
 }
56 51
 
57
-bool access_finish() {
52
+bool PersistentStore::access_finish() {
58 53
   FLASH_Lock();
59 54
   firstWrite = false;
60 55
   return true;
61 56
 }
62 57
 
63
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
58
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
64 59
   FLASH_Status status;
65 60
 
66 61
   if (firstWrite) {
@@ -95,7 +90,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
95 90
   return false;
96 91
 }
97 92
 
98
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
93
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
99 94
   for (uint16_t i = 0; i < size; i++) {
100 95
     byte* accessPoint = (byte*)(pageBase + pos + i);
101 96
     uint8_t c = *accessPoint;
@@ -106,8 +101,22 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const boo
106 101
   return false;
107 102
 }
108 103
 
109
-} // PersistentStore
110
-} // HAL
104
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
105
+  int data_pos = pos;
106
+  uint16_t crc = 0;
107
+  return write_data(data_pos, value, size, &crc);
108
+}
109
+
110
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
111
+  int data_pos = pos;
112
+  uint16_t crc = 0;
113
+  return read_data(data_pos, value, size, &crc);
114
+}
115
+
116
+const size_t PersistentStore::capacity() {
117
+  return E2END + 1;
118
+}
119
+
111 120
 
112 121
 #endif // EEPROM_SETTINGS && EEPROM FLASH
113 122
 #endif // __STM32F1__

Marlin/src/HAL/HAL_STM32F1/persistent_store_impl.cpp → Marlin/src/HAL/HAL_STM32F1/persistent_store_sdcard.cpp Ver arquivo

@@ -32,24 +32,14 @@
32 32
 #if ENABLED(EEPROM_SETTINGS) && DISABLED(FLASH_EEPROM_EMULATION)
33 33
 
34 34
 #include "../persistent_store_api.h"
35
-
36
-//#include "../../core/types.h"
37
-//#include "../../core/language.h"
38
-//#include "../../core/serial.h"
39
-//#include "../../core/utility.h"
40
-
41 35
 #include "../../sd/cardreader.h"
42 36
 
43
-
44
-namespace HAL {
45
-namespace PersistentStore {
46
-
47 37
 #define HAL_STM32F1_EEPROM_SIZE 4096
48 38
 char HAL_STM32F1_eeprom_content[HAL_STM32F1_EEPROM_SIZE];
49 39
 
50 40
 char eeprom_filename[] = "eeprom.dat";
51 41
 
52
-bool access_start() {
42
+bool PersistentStore::access_start() {
53 43
   if (!card.cardOK) return false;
54 44
   int16_t bytes_read = 0;
55 45
   constexpr char eeprom_zero = 0xFF;
@@ -62,7 +52,7 @@ bool access_start() {
62 52
   return true;
63 53
 }
64 54
 
65
-bool access_finish() {
55
+bool PersistentStore::access_finish() {
66 56
   if (!card.cardOK) return false;
67 57
   card.openFile(eeprom_filename, true);
68 58
   int16_t bytes_written = card.write(HAL_STM32F1_eeprom_content, HAL_STM32F1_EEPROM_SIZE);
@@ -70,7 +60,7 @@ bool access_finish() {
70 60
   return (bytes_written == HAL_STM32F1_EEPROM_SIZE);
71 61
 }
72 62
 
73
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
63
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
74 64
   for (int i = 0; i < size; i++)
75 65
     HAL_STM32F1_eeprom_content[pos + i] = value[i];
76 66
   crc16(crc, value, size);
@@ -78,7 +68,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
78 68
   return false;
79 69
 }
80 70
 
81
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
71
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
82 72
   for (int i = 0; i < size; i++) {
83 73
     uint8_t c = HAL_STM32F1_eeprom_content[pos + i];
84 74
     if (writing) value[i] = c;
@@ -88,10 +78,22 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const boo
88 78
   return false;
89 79
 }
90 80
 
91
-} // PersistentStore::
92
-} // HAL::
81
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
82
+  int data_pos = pos;
83
+  uint16_t crc = 0;
84
+  return write_data(data_pos, value, size, &crc);
85
+}
86
+
87
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
88
+  int data_pos = pos;
89
+  uint16_t crc = 0;
90
+  return read_data(data_pos, value, size, &crc);
91
+}
92
+
93
+const size_t PersistentStore::capacity() {
94
+  return HAL_STM32F1_EEPROM_SIZE;
95
+}
93 96
 
94 97
 #endif // EEPROM_SETTINGS
95 98
 
96 99
 #endif // __STM32F1__
97
-

Marlin/src/HAL/HAL_STM32F4/persistent_store_impl.cpp → Marlin/src/HAL/HAL_STM32F4/persistent_store_eeprom.cpp Ver arquivo

@@ -29,13 +29,10 @@
29 29
 
30 30
 #if ENABLED(EEPROM_SETTINGS)
31 31
 
32
-namespace HAL {
33
-namespace PersistentStore {
32
+bool PersistentStore::access_start() { return true; }
33
+bool PersistentStore::access_finish() { return true; }
34 34
 
35
-bool access_start() { return true; }
36
-bool access_finish() { return true; }
37
-
38
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
35
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
39 36
   while (size--) {
40 37
     uint8_t * const p = (uint8_t * const)pos;
41 38
     uint8_t v = *value;
@@ -56,7 +53,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
56 53
   return false;
57 54
 }
58 55
 
59
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing) {
56
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing) {
60 57
   do {
61 58
     uint8_t c = eeprom_read_byte((unsigned char*)pos);
62 59
     if (writing) *value = c;
@@ -67,8 +64,21 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const boo
67 64
   return false;
68 65
 }
69 66
 
70
-} // PersistentStore
71
-} // HAL
67
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
68
+  int data_pos = pos;
69
+  uint16_t crc = 0;
70
+  return write_data(data_pos, value, size, &crc);
71
+}
72
+
73
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
74
+  int data_pos = pos;
75
+  uint16_t crc = 0;
76
+  return read_data(data_pos, value, size, &crc);
77
+}
78
+
79
+const size_t PersistentStore::capacity() {
80
+  return E2END + 1;
81
+}
72 82
 
73 83
 #endif // EEPROM_SETTINGS
74 84
 #endif // STM32F4 || STM32F4xx

Marlin/src/HAL/HAL_STM32F7/persistent_store_impl.cpp → Marlin/src/HAL/HAL_STM32F7/persistent_store_eeprom.cpp Ver arquivo

@@ -24,19 +24,16 @@
24 24
 
25 25
 #ifdef STM32F7
26 26
 
27
-#include "../persistent_store_api.h"
28
-
29 27
 #include "../../inc/MarlinConfig.h"
30 28
 
31 29
 #if ENABLED(EEPROM_SETTINGS)
32 30
 
33
-namespace HAL {
34
-namespace PersistentStore {
31
+#include "../persistent_store_api.h"
35 32
 
36
-bool access_start() { return true; }
37
-bool access_finish() { return true; }
33
+bool PersistentStore::access_start() { return true; }
34
+bool PersistentStore::access_finish() { return true; }
38 35
 
39
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
36
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
40 37
   while (size--) {
41 38
     uint8_t * const p = (uint8_t * const)pos;
42 39
     uint8_t v = *value;
@@ -57,7 +54,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
57 54
   return false;
58 55
 }
59 56
 
60
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
57
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc) {
61 58
   do {
62 59
     uint8_t c = eeprom_read_byte((unsigned char*)pos);
63 60
     *value = c;
@@ -68,10 +65,21 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc) {
68 65
   return false;
69 66
 }
70 67
 
68
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
69
+  int data_pos = pos;
70
+  uint16_t crc = 0;
71
+  return write_data(data_pos, value, size, &crc);
72
+}
73
+
74
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
75
+  int data_pos = pos;
76
+  uint16_t crc = 0;
77
+  return read_data(data_pos, value, size, &crc);
71 78
 }
79
+
80
+const size_t PersistentStore::capacity() {
81
+  return E2END + 1;
72 82
 }
73 83
 
74 84
 #endif // EEPROM_SETTINGS
75 85
 #endif // STM32F7
76
-
77
-

Marlin/src/HAL/HAL_TEENSY35_36/persistent_store_impl.cpp → Marlin/src/HAL/HAL_TEENSY35_36/persistent_store_eeprom.cpp Ver arquivo

@@ -5,14 +5,12 @@
5 5
 #if ENABLED(EEPROM_SETTINGS)
6 6
 
7 7
 #include "../persistent_store_api.h"
8
+#include <avr/eeprom.h>
8 9
 
9
-namespace HAL {
10
-namespace PersistentStore {
10
+bool PersistentStore::access_start() { return true; }
11
+bool PersistentStore::access_finish() { return true; }
11 12
 
12
-bool access_start() { return true; }
13
-bool access_finish() { return true; }
14
-
15
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
13
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
16 14
   while (size--) {
17 15
     uint8_t * const p = (uint8_t * const)pos;
18 16
     uint8_t v = *value;
@@ -33,7 +31,7 @@ bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
33 31
   return false;
34 32
 }
35 33
 
36
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
34
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
37 35
   do {
38 36
     uint8_t c = eeprom_read_byte((unsigned char*)pos);
39 37
     if (writing) *value = c;
@@ -44,8 +42,21 @@ bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const boo
44 42
   return false;
45 43
 }
46 44
 
47
-} // PersistentStore
48
-} // HAL
45
+bool PersistentStore::write_data(const int pos, uint8_t* value, size_t size) {
46
+  int data_pos = pos;
47
+  uint16_t crc = 0;
48
+  return write_data(data_pos, value, size, &crc);
49
+}
50
+
51
+bool PersistentStore::read_data(const int pos, uint8_t* value, size_t size) {
52
+  int data_pos = pos;
53
+  uint16_t crc = 0;
54
+  return read_data(data_pos, value, size, &crc);
55
+}
56
+
57
+const size_t PersistentStore::capacity() {
58
+  return E2END + 1;
59
+}
49 60
 
50 61
 #endif // EEPROM_SETTINGS
51 62
 #endif // __MK64FX512__ || __MK66FX1M0__

+ 11
- 9
Marlin/src/HAL/persistent_store_api.h Ver arquivo

@@ -4,15 +4,17 @@
4 4
 #include <stddef.h>
5 5
 #include <stdint.h>
6 6
 
7
-namespace HAL {
8
-namespace PersistentStore {
7
+class PersistentStore {
8
+public:
9
+  static bool access_start();
10
+  static bool access_finish();
11
+  static bool write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc);
12
+  static bool read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing=true);
13
+  static bool write_data(const int pos, uint8_t* value, size_t size);
14
+  static bool read_data(const int pos, uint8_t* value, size_t size);
15
+  static const size_t capacity();
16
+};
9 17
 
10
-bool access_start();
11
-bool access_finish();
12
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc);
13
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing=true);
14
-
15
-} // PersistentStore
16
-} // HAL
18
+extern PersistentStore persistentStore;
17 19
 
18 20
 #endif // _PERSISTENT_STORE_H_

+ 1
- 1
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp Ver arquivo

@@ -1172,7 +1172,7 @@
1172 1172
 
1173 1173
     SERIAL_ECHO_START();
1174 1174
     SERIAL_ECHOLNPGM("EEPROM Dump:");
1175
-    for (uint16_t i = 0; i <= E2END; i += 16) {
1175
+    for (uint16_t i = 0; i < persistentStore.capacity(); i += 16) {
1176 1176
       if (!(i & 0x3)) idle();
1177 1177
       print_hex_word(i);
1178 1178
       SERIAL_ECHOPGM(": ");

+ 17
- 12
Marlin/src/module/configuration_store.cpp Ver arquivo

@@ -345,14 +345,15 @@ void MarlinSettings::postprocess() {
345 345
 
346 346
 #if ENABLED(EEPROM_SETTINGS)
347 347
   #include "../HAL/persistent_store_api.h"
348
+  PersistentStore persistentStore;
348 349
 
349 350
   #define DUMMY_PID_VALUE 3000.0f
350
-  #define EEPROM_START() int eeprom_index = EEPROM_OFFSET; HAL::PersistentStore::access_start()
351
-  #define EEPROM_FINISH() HAL::PersistentStore::access_finish()
351
+  #define EEPROM_START() int eeprom_index = EEPROM_OFFSET; persistentStore.access_start()
352
+  #define EEPROM_FINISH() persistentStore.access_finish()
352 353
   #define EEPROM_SKIP(VAR) eeprom_index += sizeof(VAR)
353
-  #define EEPROM_WRITE(VAR) HAL::PersistentStore::write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
354
-  #define EEPROM_READ(VAR) HAL::PersistentStore::read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc, !validating)
355
-  #define EEPROM_READ_ALWAYS(VAR) HAL::PersistentStore::read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
354
+  #define EEPROM_WRITE(VAR) persistentStore.write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
355
+  #define EEPROM_READ(VAR) persistentStore.read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc, !validating)
356
+  #define EEPROM_READ_ALWAYS(VAR) persistentStore.read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
356 357
   #define EEPROM_ASSERT(TST,ERR) if (!(TST)) do{ SERIAL_ERROR_START_P(port); SERIAL_ERRORLNPGM_P(port, ERR); eeprom_error = true; }while(0)
357 358
 
358 359
   #if ENABLED(DEBUG_EEPROM_READWRITE)
@@ -1607,6 +1608,10 @@ void MarlinSettings::postprocess() {
1607 1608
       }
1608 1609
     #endif
1609 1610
 
1611
+    const uint16_t MarlinSettings::meshes_end = persistentStore.capacity() - 129; // 128 (+1 because of the change to capacity rather than last valid address)
1612
+                                                                                  // is a placeholder for the size of the MAT; the MAT will always
1613
+                                                                                  // live at the very end of the eeprom
1614
+
1610 1615
     uint16_t MarlinSettings::meshes_start_index() {
1611 1616
       return (datasize() + EEPROM_OFFSET + 32) & 0xFFF8;  // Pad the end of configuration data so it can float up
1612 1617
                                                           // or down a little bit without disrupting the mesh data
@@ -1627,7 +1632,7 @@ void MarlinSettings::postprocess() {
1627 1632
         if (!WITHIN(slot, 0, a - 1)) {
1628 1633
           #if ENABLED(EEPROM_CHITCHAT)
1629 1634
             ubl_invalid_slot(a);
1630
-            SERIAL_PROTOCOLPAIR("E2END=", E2END);
1635
+            SERIAL_PROTOCOLPAIR("E2END=", persistentStore.capacity() - 1);
1631 1636
             SERIAL_PROTOCOLPAIR(" meshes_end=", meshes_end);
1632 1637
             SERIAL_PROTOCOLLNPAIR(" slot=", slot);
1633 1638
             SERIAL_EOL();
@@ -1638,9 +1643,9 @@ void MarlinSettings::postprocess() {
1638 1643
         int pos = mesh_slot_offset(slot);
1639 1644
         uint16_t crc = 0;
1640 1645
 
1641
-        HAL::PersistentStore::access_start();
1642
-        const bool status = HAL::PersistentStore::write_data(pos, (uint8_t *)&ubl.z_values, sizeof(ubl.z_values), &crc);
1643
-        HAL::PersistentStore::access_finish();
1646
+        persistentStore.access_start();
1647
+        const bool status = persistentStore.write_data(pos, (uint8_t *)&ubl.z_values, sizeof(ubl.z_values), &crc);
1648
+        persistentStore.access_finish();
1644 1649
 
1645 1650
         if (status)
1646 1651
           SERIAL_PROTOCOLPGM("?Unable to save mesh data.\n");
@@ -1676,9 +1681,9 @@ void MarlinSettings::postprocess() {
1676 1681
         uint16_t crc = 0;
1677 1682
         uint8_t * const dest = into ? (uint8_t*)into : (uint8_t*)&ubl.z_values;
1678 1683
 
1679
-        HAL::PersistentStore::access_start();
1680
-        const uint16_t status = HAL::PersistentStore::read_data(pos, dest, sizeof(ubl.z_values), &crc);
1681
-        HAL::PersistentStore::access_finish();
1684
+        persistentStore.access_start();
1685
+        const uint16_t status = persistentStore.read_data(pos, dest, sizeof(ubl.z_values), &crc);
1686
+        persistentStore.access_finish();
1682 1687
 
1683 1688
         if (status)
1684 1689
           SERIAL_PROTOCOLPGM("?Unable to load mesh data.\n");

+ 7
- 5
Marlin/src/module/configuration_store.h Ver arquivo

@@ -24,6 +24,9 @@
24 24
 #define CONFIGURATION_STORE_H
25 25
 
26 26
 #include "../inc/MarlinConfig.h"
27
+#if ENABLED(EEPROM_SETTINGS)
28
+  #include "../HAL/persistent_store_api.h"
29
+#endif
27 30
 
28 31
 #define ADD_PORT_ARG ENABLED(EEPROM_CHITCHAT) && NUM_SERIAL > 1
29 32
 
@@ -96,11 +99,10 @@ class MarlinSettings {
96 99
 
97 100
       static bool eeprom_error, validating;
98 101
 
99
-      #if ENABLED(AUTO_BED_LEVELING_UBL) // Eventually make these available if any leveling system
100
-                                         // That can store is enabled
101
-        static constexpr uint16_t meshes_end = E2END - 128; // 128 is a placeholder for the size of the MAT; the MAT will always
102
-                                                            // live at the very end of the eeprom
103
-
102
+      #if ENABLED(AUTO_BED_LEVELING_UBL)  // Eventually make these available if any leveling system
103
+                                          // That can store is enabled
104
+        static const uint16_t meshes_end; // 128 is a placeholder for the size of the MAT; the MAT will always
105
+                                          // live at the very end of the eeprom
104 106
       #endif
105 107
 
106 108
       static bool _load(PORTINIT_SOLO);

Carregando…
Cancelar
Salvar