Переглянути джерело

[2.0.x] PersistentStore update followup (#11549)

Chris Pepper 6 роки тому
джерело
коміт
5573ef62c6

+ 0
- 51
Marlin/src/HAL/HAL_AVR/persistent_store_impl.cpp Переглянути файл

1
-#ifdef __AVR__
2
-
3
-#include "../shared/persistent_store_api.h"
4
-
5
-#include "../../inc/MarlinConfig.h"
6
-
7
-#if ENABLED(EEPROM_SETTINGS)
8
-
9
-namespace HAL {
10
-namespace PersistentStore {
11
-
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) {
16
-  while (size--) {
17
-    uint8_t * const p = (uint8_t * const)pos;
18
-    uint8_t v = *value;
19
-    // EEPROM has only ~100,000 write cycles,
20
-    // so only write bytes that have changed!
21
-    if (v != eeprom_read_byte(p)) {
22
-      eeprom_write_byte(p, v);
23
-      if (eeprom_read_byte(p) != v) {
24
-        SERIAL_ECHO_START();
25
-        SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
26
-        return true;
27
-      }
28
-    }
29
-    crc16(crc, &v, 1);
30
-    pos++;
31
-    value++;
32
-  };
33
-  return false;
34
-}
35
-
36
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
37
-  do {
38
-    uint8_t c = eeprom_read_byte((unsigned char*)pos);
39
-    if (writing) *value = c;
40
-    crc16(crc, &c, 1);
41
-    pos++;
42
-    value++;
43
-  } while (--size);
44
-  return false;  // always assume success for AVR's
45
-}
46
-
47
-}
48
-}
49
-
50
-#endif // EEPROM_SETTINGS
51
-#endif // __AVR__

+ 1
- 2
Marlin/src/HAL/HAL_DUE/Servo_Due.cpp Переглянути файл

45
 #if HAS_SERVOS
45
 #if HAS_SERVOS
46
 
46
 
47
 #include <Arduino.h>
47
 #include <Arduino.h>
48
-#include "../servo.h"
48
+#include "../shared/servo.h"
49
 #include "../shared/servo_private.h"
49
 #include "../shared/servo_private.h"
50
 
50
 
51
 static volatile int8_t Channel[_Nbr_16timers];              // counter for the servo being pulsed for each timer (or -1 if refresh interval)
51
 static volatile int8_t Channel[_Nbr_16timers];              // counter for the servo being pulsed for each timer (or -1 if refresh interval)
158
 #endif // HAS_SERVOS
158
 #endif // HAS_SERVOS
159
 
159
 
160
 #endif // ARDUINO_ARCH_SAM
160
 #endif // ARDUINO_ARCH_SAM
161
-

+ 5
- 0
Marlin/src/HAL/HAL_DUE/persistent_store_eeprom.cpp Переглянути файл

26
 
26
 
27
 #if ENABLED(EEPROM_SETTINGS)
27
 #if ENABLED(EEPROM_SETTINGS)
28
 
28
 
29
+#include "../../inc/MarlinConfig.h"
29
 #include "../shared/persistent_store_api.h"
30
 #include "../shared/persistent_store_api.h"
30
 
31
 
32
+#if DISABLED(I2C_EEPROM) && DISABLED(SPI_EEPROM)
33
+  #define E2END 0xFFF // Default to Flash emulated EEPROM size (EepromEmulation_Due.cpp)
34
+#endif
35
+
31
 extern void eeprom_flush(void);
36
 extern void eeprom_flush(void);
32
 
37
 
33
 bool PersistentStore::access_start() { return true; }
38
 bool PersistentStore::access_start() { return true; }

+ 0
- 59
Marlin/src/HAL/HAL_DUE/persistent_store_impl.cpp Переглянути файл

1
-#ifdef ARDUINO_ARCH_SAM
2
-
3
-#include "../shared/persistent_store_api.h"
4
-
5
-#include "../../inc/MarlinConfig.h"
6
-
7
-#if ENABLED(EEPROM_SETTINGS)
8
-
9
-extern void eeprom_flush(void);
10
-
11
-namespace HAL {
12
-namespace PersistentStore {
13
-
14
-bool access_start() { return true; }
15
-
16
-bool access_finish() {
17
-  #if DISABLED(I2C_EEPROM) && DISABLED(SPI_EEPROM)
18
-    eeprom_flush();
19
-  #endif
20
-  return true;
21
-}
22
-
23
-bool write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
24
-  while (size--) {
25
-    uint8_t * const p = (uint8_t * const)pos;
26
-    uint8_t v = *value;
27
-    // EEPROM has only ~100,000 write cycles,
28
-    // so only write bytes that have changed!
29
-    if (v != eeprom_read_byte(p)) {
30
-      eeprom_write_byte(p, v);
31
-      if (eeprom_read_byte(p) != v) {
32
-        SERIAL_ECHO_START();
33
-        SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
34
-        return true;
35
-      }
36
-    }
37
-    crc16(crc, &v, 1);
38
-    pos++;
39
-    value++;
40
-  };
41
-  return false;
42
-}
43
-
44
-bool read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
45
-  do {
46
-    uint8_t c = eeprom_read_byte((unsigned char*)pos);
47
-    if (writing) *value = c;
48
-    crc16(crc, &c, 1);
49
-    pos++;
50
-    value++;
51
-  } while (--size);
52
-  return false;
53
-}
54
-
55
-}
56
-}
57
-
58
-#endif // EEPROM_SETTINGS
59
-#endif // __AVR__

+ 6
- 7
Marlin/src/HAL/HAL_LPC1768/persistent_store_flash.cpp Переглянути файл

41
 #if ENABLED(EEPROM_SETTINGS)
41
 #if ENABLED(EEPROM_SETTINGS)
42
 
42
 
43
 #include "persistent_store_api.h"
43
 #include "persistent_store_api.h"
44
+#include "../../inc/MarlinConfig.h"
44
 
45
 
45
 #if ENABLED(FLASH_EEPROM)
46
 #if ENABLED(FLASH_EEPROM)
46
 
47
 
50
 
51
 
51
 #define SECTOR_START(sector)	((sector < 16) ? (sector * 0x1000) : ((sector - 14) * 0x8000))
52
 #define SECTOR_START(sector)	((sector < 16) ? (sector * 0x1000) : ((sector - 14) * 0x8000))
52
 #define EEPROM_SECTOR 29
53
 #define EEPROM_SECTOR 29
53
-#define EEPROM_SIZE (E2END+1)
54
+#define EEPROM_SIZE (4096)
54
 #define SECTOR_SIZE (32768)
55
 #define SECTOR_SIZE (32768)
55
 #define EEPROM_SLOTS (SECTOR_SIZE/EEPROM_SIZE)
56
 #define EEPROM_SLOTS (SECTOR_SIZE/EEPROM_SIZE)
56
 #define EEPROM_ERASE (0xff)
57
 #define EEPROM_ERASE (0xff)
57
 #define SLOT_ADDRESS(sector, slot) (((uint8_t *)SECTOR_START(sector)) + slot * EEPROM_SIZE)
58
 #define SLOT_ADDRESS(sector, slot) (((uint8_t *)SECTOR_START(sector)) + slot * EEPROM_SIZE)
58
 
59
 
59
-#if EEPROM_SIZE != 4096
60
-  #error "EEPROM_SIZE must match flash write size"
61
-#endif
62
-
63
 static uint8_t ram_eeprom[EEPROM_SIZE];
60
 static uint8_t ram_eeprom[EEPROM_SIZE];
64
 static bool eeprom_dirty = false;
61
 static bool eeprom_dirty = false;
65
 static int current_slot = 0;
62
 static int current_slot = 0;
118
   return true;
115
   return true;
119
 }
116
 }
120
 
117
 
121
-bool PersistentStore::write_data(int &pos, const uint8_t *value, uint16_t size, uint16_t *crc) {
118
+bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
122
   for (int i = 0; i < size; i++) ram_eeprom[pos + i] = value[i];
119
   for (int i = 0; i < size; i++) ram_eeprom[pos + i] = value[i];
123
   eeprom_dirty = true;
120
   eeprom_dirty = true;
124
   crc16(crc, value, size);
121
   crc16(crc, value, size);
126
   return false;  // return true for any error
123
   return false;  // return true for any error
127
 }
124
 }
128
 
125
 
129
-bool PersistentStore::read_data(int &pos, uint8_t* value, uint16_t size, uint16_t *crc, const bool writing/*=true*/) {
126
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
130
   const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos];
127
   const uint8_t * const buff = writing ? &value[0] : &ram_eeprom[pos];
131
   if (writing) for (int i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
128
   if (writing) for (int i = 0; i < size; i++) value[i] = ram_eeprom[pos + i];
132
   crc16(crc, buff, size);
129
   crc16(crc, buff, size);
134
   return false;  // return true for any error
131
   return false;  // return true for any error
135
 }
132
 }
136
 
133
 
134
+size_t PersistentStore::capacity() { return EEPROM_SIZE; }
135
+
137
 #endif // FLASH_EEPROM
136
 #endif // FLASH_EEPROM
138
 #endif // EEPROM_SETTINGS
137
 #endif // EEPROM_SETTINGS
139
 #endif // TARGET_LPC1768
138
 #endif // TARGET_LPC1768

+ 4
- 3
Marlin/src/HAL/HAL_LPC1768/persistent_store_sdcard.cpp Переглянути файл

26
 
26
 
27
 #if ENABLED(EEPROM_SETTINGS)
27
 #if ENABLED(EEPROM_SETTINGS)
28
 
28
 
29
+#include "../../inc/MarlinConfig.h"
29
 #include "persistent_store_api.h"
30
 #include "persistent_store_api.h"
30
 
31
 
31
 #if DISABLED(FLASH_EEPROM)
32
 #if DISABLED(FLASH_EEPROM)
80
 static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) {
81
 static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) {
81
   const char * const rw_str = write ? PSTR("write") : PSTR("read");
82
   const char * const rw_str = write ? PSTR("write") : PSTR("read");
82
   SERIAL_PROTOCOLCHAR(' ');
83
   SERIAL_PROTOCOLCHAR(' ');
83
-  serialprint_PGM(rw_str);
84
+  serialprintPGM(rw_str);
84
   SERIAL_PROTOCOLPAIR("_data(", pos);
85
   SERIAL_PROTOCOLPAIR("_data(", pos);
85
   SERIAL_PROTOCOLPAIR(",", (int)value);
86
   SERIAL_PROTOCOLPAIR(",", (int)value);
86
   SERIAL_PROTOCOLPAIR(",", (int)size);
87
   SERIAL_PROTOCOLPAIR(",", (int)size);
87
   SERIAL_PROTOCOLLNPGM(", ...)");
88
   SERIAL_PROTOCOLLNPGM(", ...)");
88
   if (total) {
89
   if (total) {
89
     SERIAL_PROTOCOLPGM(" f_");
90
     SERIAL_PROTOCOLPGM(" f_");
90
-    serialprint_PGM(rw_str);
91
+    serialprintPGM(rw_str);
91
     SERIAL_PROTOCOLPAIR("()=", (int)s);
92
     SERIAL_PROTOCOLPAIR("()=", (int)s);
92
     SERIAL_PROTOCOLPAIR("\n size=", size);
93
     SERIAL_PROTOCOLPAIR("\n size=", size);
93
     SERIAL_PROTOCOLPGM("\n bytes_");
94
     SERIAL_PROTOCOLPGM("\n bytes_");
94
-    serialprint_PGM(write ? PSTR("written=") : PSTR("read="));
95
+    serialprintPGM(write ? PSTR("written=") : PSTR("read="));
95
     SERIAL_PROTOCOLLN(total);
96
     SERIAL_PROTOCOLLN(total);
96
   }
97
   }
97
   else
98
   else

Marlin/src/HAL/shared/platforms.h → Marlin/src/HAL/platforms.h Переглянути файл


+ 1
- 2
Marlin/src/HAL/shared/I2cEeprom.cpp Переглянути файл

33
 // Includes
33
 // Includes
34
 // --------------------------------------------------------------------------
34
 // --------------------------------------------------------------------------
35
 
35
 
36
-#include HAL_PATH(., HAL.h)
36
+#include HAL_PATH(.., HAL.h)
37
 #include <Wire.h>
37
 #include <Wire.h>
38
 
38
 
39
 // --------------------------------------------------------------------------
39
 // --------------------------------------------------------------------------
157
 
157
 
158
 
158
 
159
 #endif // ENABLED(I2C_EEPROM)
159
 #endif // ENABLED(I2C_EEPROM)
160
-

+ 1
- 1
Marlin/src/HAL/shared/SpiEeprom.cpp Переглянути файл

29
 
29
 
30
 #if ENABLED(SPI_EEPROM)
30
 #if ENABLED(SPI_EEPROM)
31
 
31
 
32
-#include HAL_PATH(., HAL.h)
32
+#include HAL_PATH(.., HAL.h)
33
 
33
 
34
 #define CMD_WREN  6   // WREN
34
 #define CMD_WREN  6   // WREN
35
 #define CMD_READ  2   // WRITE
35
 #define CMD_READ  2   // WRITE

Marlin/src/HAL/persistent_store_api.cpp → Marlin/src/HAL/shared/persistent_store_api.cpp Переглянути файл

20
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
20
  * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
  *
21
  *
22
  */
22
  */
23
-#include "../inc/MarlinConfigPre.h"
23
+#include "../../inc/MarlinConfigPre.h"
24
 
24
 
25
 #if ENABLED(EEPROM_SETTINGS)
25
 #if ENABLED(EEPROM_SETTINGS)
26
 
26
 
27
-  #include "shared/persistent_store_api.h"
27
+  #include "persistent_store_api.h"
28
   PersistentStore persistentStore;
28
   PersistentStore persistentStore;
29
 
29
 
30
 #endif
30
 #endif

+ 1
- 1
Marlin/src/inc/MarlinConfigPre.h Переглянути файл

23
 #ifndef _MARLIN_CONFIGPRE_H_
23
 #ifndef _MARLIN_CONFIGPRE_H_
24
 #define _MARLIN_CONFIGPRE_H_
24
 #define _MARLIN_CONFIGPRE_H_
25
 
25
 
26
-#include "../HAL/shared/platforms.h"
26
+#include "../HAL/platforms.h"
27
 #include "../core/boards.h"
27
 #include "../core/boards.h"
28
 #include "../core/macros.h"
28
 #include "../core/macros.h"
29
 #include "../core/types.h"
29
 #include "../core/types.h"

+ 2
- 2
buildroot/share/tests/DUE_tests Переглянути файл

5
 
5
 
6
 restore_configs
6
 restore_configs
7
 opt_set MOTHERBOARD BOARD_RAMPS4DUE_EFB
7
 opt_set MOTHERBOARD BOARD_RAMPS4DUE_EFB
8
-opt_enable S_CURVE_ACCELERATION
8
+opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS
9
 opt_set E0_AUTO_FAN_PIN 8
9
 opt_set E0_AUTO_FAN_PIN 8
10
 opt_set EXTRUDER_AUTO_FAN_SPEED 100
10
 opt_set EXTRUDER_AUTO_FAN_SPEED 100
11
-exec_test $1 $2 "RAMPS4DUE_EFB S_CURVE_ACCELERATION"
11
+exec_test $1 $2 "RAMPS4DUE_EFB S_CURVE_ACCELERATION EEPROM_SETTINGS"

+ 2
- 2
buildroot/share/tests/LPC1768_tests Переглянути файл

14
 
14
 
15
 restore_configs
15
 restore_configs
16
 opt_set MOTHERBOARD BOARD_MKS_SBASE
16
 opt_set MOTHERBOARD BOARD_MKS_SBASE
17
-opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT
18
-exec_test $1 $2 "MKS SBASE RRDFG SDSUPPORT"
17
+opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS
18
+exec_test $1 $2 "MKS SBASE RRDFG SDSUPPORT EEPROM_SETTINGS"
19
 
19
 
20
 #clean up
20
 #clean up
21
 restore_configs
21
 restore_configs

Завантаження…
Відмінити
Зберегти